## page was renamed from urdf/XML/Sensor ## title = sensor ## description = Describes a sensor, such as a camera, ray sensor, etc ## XMLCategory ''' /!\ The sensor element has been implemented in the URDF Dom but has never really been used in application. This is a project that was dropped anyone is encouraged to pick it up and extend it to sensor hardware applications. Please contribute! ''' <> == element == The sensor element describes basic properties of a visual sensor (i.e. camera / ray sensor). Here is an example of a camera sensor element: {{{#!xml }}} ## {{attachment:sensor_camera.png||height="285",width="515"}} And below is an example of a laser scan (ray) sensor element: {{{#!xml }}} ## {{attachment:sensor_ray.png||height="285",width="515"}} == Attributes == . '''name''' ''(required) (string)'' . The name of the link itself . '''update_rate''' ''(optional) (float) (Hz)'' . The frequency at which the sensor data is generated. If left unspecified, the sensor will generate data every cycle. == Elements == . '''''' ''(required)'' . '''link''' ''(required) (string)'' . The name of the link this sensor is attached to. '''''' ''(optional: defaults to identity if not specified)'' . This is the pose of the sensor optical frame, relative to the sensor parent reference frame. The sensor optical frame adopts the conventions of z-forward, x-right and y-down. . '''xyz''' ''(optional: defaults to zero vector)'' . Represents the <> offset. . '''rpy''' ''(optional: defaults to identity if not specified)'' . Represents the fixed axis roll, pitch and yaw angles in radians. . '''''' ''(optional)'' . '''''' ''(required)'' . '''width''' ''(required) (unsigned int) (pixels)'' . Width of the camera in pixels. . '''height''' ''(required) (unsigned int) (pixels)'' . Height of the camera in pixels. . '''format''' ''(required) (string)'' . Image format of the camera. Can be any of the strings defined in [[https://code.ros.org/trac/ros-pkg/browser/stacks/common_msgs/trunk/sensor_msgs/include/sensor_msgs/image_encodings.h|image_encodings.h insdie sensor_msgs]]. . '''hfov''' ''(required) (float) (radians)'' . Horizontal field of view of the camera . '''near''' ''(required) (float) (m)'' . Near clip distance of the camera in meters. . '''far''' ''(required) (float) (m)'' . Far clip distance of the camera in meters. This needs to be greater or equal to near clip. . '''''' ''(optional)'' . '''''' ''(optional)'' . '''samples''' ''(optional: default 1) (unsigned int)'' . The number of simulated rays to generate per complete laser sweep cycle. . '''resolution''' ''(optional: default 1) (float)'' . This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. . '''min_angle''' ''(optional: default 0) (float) (radians)'' . '''max_angle''' ''(optional: default 0) (float) (radians)'' . Must be greater or equal to min_angle . '''''' ''(optional)'' . '''samples''' ''(optional: default 1) (unsigned int)'' . The number of simulated rays to generate per complete laser sweep cycle. . '''resolution''' ''(optional: default 1) (float)'' . This number is multiplied by samples to determine the number of range data points returned. If resolution is less than one, range data is interpolated. If resolution is greater than one, range data is averaged. . '''min_angle''' ''(optional: default 0) (float) (radians)'' . '''max_angle''' ''(optional: default 0) (float) (radians)'' . Must be greater or equal to min_angle == Recommended Camera or Ray Resolution == * In [[gazebo|simulation]], large sensors will slow down overall performance. Depending on update rates required, it is recommended to keep the camera or ray resolution and update rates as low as possible. ## see [[http://gazebosim.org/wiki/sdf_sensor]] for reference and comparison. == Proposal for New Type of Sensor == [[urdf/XML/sensor/proposals]]