Semantic camera =============== **A smart camera allowing to retrieve objects in its field of view** This sensor emulates a high level *abstract* camera that outputs the name and 6D pose of visible objects (*i.e.* objects in the field of view of the camera). It also outputs the *type* of the object if the ``Type`` property is set (:python:`my_object.properties(Type="Bottle")` for instance). General usage ------------- You need to *tag* the objects you want your camera to track by either adding a boolean property ``Object`` to your object: :python:`my_object.properties(Object=True)`, or by setting a *type* and using this type as the value of the ``tag`` property of the camera: .. code-block:: python object_to_track = PassiveObject(...) object_to_track.properties(Type="Bottle") ... semcam = SemanticCamera() semcam.properties(tag="Bottle") ... See the *Examples* section below for a complete working example. If the ``Label`` property is defined, it is used as exported name. Otherwise, the Blender object name is used. By default, the pose of the objects is provided in the **world** frame. When setting the ``relative`` property to ``True`` (:python:`semcam.properties(relative=True)`), the pose is computed in the **camera** frame instead. Details of implementation ------------------------- A test is made to identify which of these objects are inside of the view frustum of the camera. Finally, a single visibility test is performed by casting a ray from the center of the camera to the center of the object. If anything other than the test object is found first by the ray, the object is considered to be occluded by something else, even if it is only the center that is being blocked. This occulsion check can be deactivated (for slightly improved performances) by setting the sensor property ``noocclusion`` to ``True``. See also :doc:`../sensors/camera` for generic informations about MORSE cameras. .. cssclass:: properties morse-section Configuration parameters for Semantic camera -------------------------------------------- You can set these properties in your scripts with ``.properties(=..., =...)``. - ``cam_width`` (default: ``256``) (no documentation available yet) - ``cam_height`` (default: ``256``) (no documentation available yet) - ``cam_focal`` (default: ``25.0``) (no documentation available yet) - ``cam_near`` (default: ``0.1``) (no documentation available yet) - ``cam_far`` (default: ``100.0``) (no documentation available yet) - ``Vertical_Flip`` (default: ``True``) (no documentation available yet) - ``retrieve_depth`` (default: ``False``) (no documentation available yet) - ``retrieve_zbuffer`` (default: ``False``) (no documentation available yet) - ``relative`` (bool, default: ``False``) Return object position relatively to the sensor frame. - ``noocclusion`` (bool, default: ``False``) Do not check for objects possibly hiding each others (faster but less realistic behaviour) - ``tag`` (string, default: ``"Object"``) The type of detected objects. This type is looked for as a game property of scene objects or as their 'Type' property. You must then add fix this property to the objects you want to be detected by the semantic camera. .. cssclass:: fields morse-section Data fields ----------- This sensor exports these datafields at each simulation step: - ``timestamp`` (float, initial value: ``0.0``) number of seconds in simulated time - ``visible_objects`` (list, initial value: ``[]``) A list containing the different objects visible by the camera. Each object is represented by a dictionary composed of: - **name** (String): the name of the object - **type** (String): the type of the object - **position** (vec3): the position of the object, in meter, in the blender frame - **orientation** (quaternion): the orientation of the object, in the blender frame *Interface support:* - :tag:`pocolibs` as `VimanObjectPublicArray `_ (:py:mod:`morse.middleware.pocolibs.sensors.viman.VimanPoster`) - :tag:`ros` as `std_msgs/String `_ (:py:mod:`morse.middleware.ros.semantic_camera.SemanticCameraPublisher`) or as `std_msgs/String `_ (:py:mod:`morse.middleware.ros.semantic_camera.SemanticCameraPublisherLisp`) - :tag:`socket` as straight JSON serialization (:py:mod:`morse.middleware.socket_datastream.SocketPublisher`) - :tag:`yarp` as yarp::Bottle (:py:mod:`morse.middleware.yarp_datastream.YarpPublisher`) .. cssclass:: services morse-section Services for Semantic camera ---------------------------- - ``get_properties()`` (blocking) Returns the properties of a component. - Return value a dictionary of the current component's properties - ``get_local_data()`` (blocking) Returns the current data stored in the sensor. - Return value a dictionary of the current sensor's data - ``set_property(prop_name, prop_val)`` (blocking) Modify one property on a component - Parameters - ``prop_name``: the name of the property to modify (as shown the documentation) - ``prop_val``: the new value of the property. Note that there is no checking about the type of the value so be careful - Return value nothing - ``get_configurations()`` (blocking) Returns the configurations of a component (parsed from the properties). - Return value a dictionary of the current component's configurations .. cssclass:: examples morse-section Examples -------- The following examples show how to use this component in a *Builder* script: .. code-block:: python # add a 'passive' object visible to the semantic cameras table = PassiveObject('props/objects','SmallTable') table.translate(x=3.5, y=-3, z=0) table.rotate(z=0.2) # by setting the 'Object' property to true, this object becomes # visible to the semantic cameras present in the simulation. # Note that you can set this property on any object (other robots, humans,...). table.properties(Type = "table", Label = "MY_FAVORITE_TABLE") # then, create a robot robot = Morsy() # creates a new instance of the sensor, that tracks all tables. # If you do not specify a particular 'tag', the camera tracks by default # all object with the properties 'type="Object"' or 'Object=True'. semcam = SemanticCamera() semcam.properties(tag = "table") # place the camera at the correct location semcam.translate(, , ) semcam.rotate(, , ) robot.append(semcam) # define one or several communication interface, like 'socket' semcam.add_interface() env = Environment('empty') .. cssclass:: files morse-section Other sources of examples +++++++++++++++++++++++++ - `Source code <../../_modules/morse/sensors/semantic_camera.html>`_ - `Unit-test <../../_modules/base/semantic_camera_testing.html>`_ *(This page has been auto-generated from MORSE module morse.sensors.semantic_camera.)*