diff --git a/README.md b/README.md index 0c755b88..ccaea90e 100644 --- a/README.md +++ b/README.md @@ -3,7 +3,8 @@ urdfdom The URDF (U-Robot Description Format) library provides core data structures and a simple XML parsers for populating the class data structures from an URDF file. -For now, the details of the URDF specifications reside on http://ros.org/wiki/urdf +The details of the URDF specifications reside in the [specification folder](specification) in this repo. + ### Using with ROS diff --git a/specification/README.md b/specification/README.md new file mode 100644 index 00000000..e192cb0f --- /dev/null +++ b/specification/README.md @@ -0,0 +1,47 @@ +# XML Robot Description Format (URDF) + +The Unified Robot Description Format (URDF) is an XML specification to describe a robot. We attempt to keep this specification as general as possible, but obviously the specification cannot describe all robots. The main limitation at this point is that only tree structures can be represented, ruling out all parallel robots. Also, the specification assumes the robot consists of rigid links connected by joints; flexible elements are not supported. The specification covers: + + * Kinematic and dynamic description of the robot + * Visual representation of the robot + * Collision model of the robot + + Link + +The description of a robot consists of a set of [link elements](./link.md), and a set of [joint elements](./joint.md) connecting the links together. So a typical robot description looks something like this: + +~~~xml + + + + ... + ... + ... + + .... + .... + .... + +~~~ + +You can see that the root element of the URDF format is a `` element. + +## `` element + +The `` element describes all properties of a robot. For details on the root description format, check out the [robot element](./robot.md) page. + +## `` element + +For details on the `` description format, check out the [link element](./link.md) page. + +## `` element + +For details on the `` description format, check out the [joint element](./joint.md) page. + +## `` element + +For details on the `` description format, check out the [gazebo element](./gazebo.md) page. + +## `` element + +For details on the `` description format, check out the [sensor element](./sensor.md) page. \ No newline at end of file diff --git a/specification/cylinder_coordinates.png b/specification/cylinder_coordinates.png new file mode 100644 index 00000000..828b9ba6 Binary files /dev/null and b/specification/cylinder_coordinates.png differ diff --git a/specification/gazebo.md b/specification/gazebo.md new file mode 100644 index 00000000..e8bdd9fe --- /dev/null +++ b/specification/gazebo.md @@ -0,0 +1,5 @@ +# `` element + +The gazebo element is an extension to the URDF robot description format, used for simulation purposes in the [Gazebo](https://gazebosim.org/) simulator. + +For full documentation of the Gazebo element, see [Using A URDF In Gazebo](http://gazebosim.org/tutorials?tut=ros_urdf&cat=connect_ros) (for Gazebo Classic) or [SDFormat extensions to URDF (the `` tag)](http://sdformat.org/tutorials?tut=sdformat_urdf_extensions&cat=specification&) (for new Gazebo). \ No newline at end of file diff --git a/specification/inertial.png b/specification/inertial.png new file mode 100644 index 00000000..71048119 Binary files /dev/null and b/specification/inertial.png differ diff --git a/specification/joint.md b/specification/joint.md new file mode 100644 index 00000000..a6fd4fe7 --- /dev/null +++ b/specification/joint.md @@ -0,0 +1,132 @@ +# `` element + +The joint element describes the kinematics and dynamics of the joint and also specifies the [safety limits](http://wiki.ros.org/pr2_controller_manager/safety_limits) of the joint. + +![example-joint](./joint.png) + +## Attributes + +| attribute | type | use | default value | description | +| --------- | ----------- | -------- | ------------- | ------------------------------------------------------------------------------ | +| `name` | `string` | required | NA | Specifies a unique name of the join. | +| `type` | `JointType` | required | NA | Specifies the type of joint, see "Type: `JointType`" section for more details. | + +### Type: `JointType` + +where type can be one of the following: +- `revolute`: a hinge joint that rotates along the axis and has a limited range specified by the upper and lower limits. +- `continuous`: a continuous hinge joint that rotates around the axis and has no upper and lower limits. +- `prismatic`: a sliding joint that slides along the axis, and has a limited range specified by the upper and lower limits. +- `fixed`: this is not really a joint because it cannot move. All degrees of freedom are locked. This type of joint does not require the ``, ``, ``, `` or ``. +- `floating`: this joint allows motion for all 6 degrees of freedom. +- `planar`: this joint allows motion in a plane perpendicular to the axis. + +## Elements + +The joint element has following elements: + +| element | use | +| ------------------------------------------- | -------------------------------------------------------------------------------------------------- | +| [``](#parent) | required | +| [``](#child) | required | +| [``](#origin) | optional: defaults to identity if not specified | +| [``](#axis) | optional: defaults to (1,0,0) | +| [``](#calibration) | optional | +| [``](#dynamics) | optional | +| [``](#limit) | required only for revolute and prismatic joint | +| [``](#mimic) | optional (New with ROS Groovy. See [issue](https://github.com/ros/robot_state_publisher/issues/1)) | +| [``](#safety_controller) | optional | + +### `` + +This is the transform from the parent link to the child link. The joint is located at the origin of the child link, as shown in the figure above. + +| attribute | type | use | default value | description | +| --------- | -------- | -------- | ------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | +| `xyz` | `string` | optional | zero vector | Represents the x, y, z offset. All positions are specified in metres. | +| `rpy` | `string` | optional | zero vector | Represents the rotation around fixed axis: first roll around x, then pitch around y and finally yaw around z. All angles are specified in radians. | + +### `` + +| attribute | type | use | default value | description | +| --------- | -------- | -------- | ------------- | --------------------------------------------------------------------------------- | +| `link` | `string` | required | NA | The name of the link that is the parent of this link in the robot tree structure. | + +### `` + +| attribute | type | use | default value | description | +| --------- | ------ | -------- | ------------- | -------------------------------------------- | +| `link` | `string` | required | NA | The name of the link that is the child link. | + +### `` + +The joint axis specified in the joint frame. This is the axis of rotation for revolute joints, the axis of translation for prismatic joints, and the surface normal for planar joints. The axis is specified in the joint frame of reference. Fixed and floating joints do not use the axis field. + +| attribute | type | use | default value | description | +| --------- | -------- | -------- | ------------- | --------------------------------------------------------------------------------- | +| `xyz` | `string` | required | NA | Represents the (x, y, z) components of a vector. The vector should be normalized. | + +### `` + +The reference positions of the joint, used to calibrate the absolute position of the joint. + +| attribute | type | use | default value | description | +| --------- | -------- | -------- | ------------- | -------------------------------------------------------------------------------------------------- | +| `rising` | `double` | optional | ??? | When the joint moves in a positive direction, this reference position will trigger a rising edge. | +| `falling` | `double` | optional | ??? | When the joint moves in a positive direction, this reference position will trigger a falling edge. | + +### `` + +An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. + +| attribute | type | use | default value | description | +| ---------- | -------- | -------- | ------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `damping` | `double` | optional | defaults to 0 | The physical damping value of the joint (in newton-seconds per metre [N∙s/m] for prismatic joints, in newton-metre-seconds per radian [N∙m∙s/rad] for revolute joints). | +| `friction` | `double` | optional | defaults to 0 | The physical static friction value of the joint (in newtons [N] for prismatic joints, in newton-metres [N∙m] for revolute joints). | + +### `` + +(required only for revolute and prismatic joint) + +| attribute | type | use | default value | description | +| ---------- | -------- | -------- | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| `effort` | `double` | required | NA | An attribute for enforcing the maximum joint effort (\|applied effort\| < \|effort\|). See safety limits. | +| `velocity` | `double` | required | NA | An attribute for enforcing the maximum joint velocity (in radians per second [rad/s] for revolute joints, in metres per second [m/s] for prismatic joints). [See safety limits](http://wiki.ros.org/pr2_controller_manager/safety_limits). | +| `lower` | `double` | optional | defaults to 0 | An attribute specifying the lower joint limit (in radians for revolute joints, in metres for prismatic joints). Omit if joint is continuous. | +| `upper` | `double` | optional | defaults to 0 | An attribute specifying the upper joint limit (in radians for revolute joints, in metres for prismatic joints). Omit if joint is continuous. | + +### `` + +(optional) (New with ROS Groovy. See issue) + +This tag is used to specify that the defined joint mimics another existing joint. The value of this joint can be computed as value = multiplier * other_joint_value + offset. + +| attribute | type | use | default value | description | +| ------------ | -------- | -------- | ------------- | -------------------------------------------------------------------------------------------------------------------------- | +| `joint` | `string` | required | NA | This specifies the name of the joint to mimic. | +| `multiplier` | `double` | optional | defaults to 1 | Specifies the multiplicative factor in the formula above. | +| `offset` | `double` | optional | defaults to 0 | Specifies the offset to add in the formula above. Defaults to 0 (radians for revolute joints, meters for prismatic joints) | + +### `` + +| attribute | type | use | default value | description | +| ------------------ | -------- | -------- | ------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `k_velocity` | `double` | required | NA | An attribute specifying the relation between effort and velocity limits. See See safety limits for more details. | +| `soft_lower_limit` | `double` | optional | defaults to 0 | An attribute specifying the lower joint boundary where the safety controller starts limiting the position of the joint. This limit needs to be larger than the lower joint limit (see above). See [safety limits](http://wiki.ros.org/pr2_controller_manager/safety_limits) for more details. | +| `soft_upper_limit` | `double` | optional | defaults to 0 | An attribute specifying the upper joint boundary where the safety controller starts limiting the position of the joint. This limit needs to be smaller than the upper joint limit (see above). See [safety limits](http://wiki.ros.org/pr2_controller_manager/safety_limits) for more details. | +| `k_position` | `double` | optional | defaults to 0 | An attribute specifying the relation between position and velocity limits. See [safety limits](http://wiki.ros.org/pr2_controller_manager/safety_limits) for more details. | + +## Example + +```xml + + + + + + + + + + +``` \ No newline at end of file diff --git a/specification/joint.png b/specification/joint.png new file mode 100644 index 00000000..d3f43371 Binary files /dev/null and b/specification/joint.png differ diff --git a/specification/link.md b/specification/link.md new file mode 100644 index 00000000..8df5f94a --- /dev/null +++ b/specification/link.md @@ -0,0 +1,234 @@ +# `` element + +The link element describes a rigid body with an inertia, visual features, and collision properties. + +Inertial + +## Attributes + +| `` attr | type | use | default value | description | +| ------------- | -------- | -------- | ------------- | ---------------------------- | +| `name` | `string` | required | NA | The name of the link itself. | + +## Elements + +The link element has following child elements: + +| `` element | use | description | +| --------------------------- | -------------------------------------------------------------------- | ----------------------------------- | +| [``](#visual) | optional | The visual properties of the link. | +| [``](#collision) | optional | The collision properties of a link. | +| [``](#inertial) | optional: defaults to a zero mass and zero inertial if not specified | The visual properties of the link. | + +### `` + +The visual properties of the link. This element specifies the shape of the object (box, cylinder, etc.) for visualization purposes. + +> [!NOTE] +> multiple instances of `` tags can exist for the same link. The union of the geometry they define forms the visual representation of the link. + +| `` attr | type | use | default value | description | +| --------------- | -------- | -------- | ------------- | -------------------------------------------------------------------------------------------------------------------------------- | +| `name` | `string` | optional | none | Specifies a name for a part of a link's geometry. This is useful to be able to refer to specific bits of the geometry of a link. | + +Child elements of a `visual` element: +| `` element | use | description | +| -------------------------------- | ----------------------------------------------- | ------------------------------------------------------------------------------------------ | +| [``](#visual-geometry) | required | The shape of the visual object. | +| [``](#visual-origin) | optional: defaults to identity if not specified | The reference frame of the visual element with respect to the reference frame of the link. | +| [``](#visual-material) | optional | The material of the visual element. | + +#### visual: `` + +The reference frame of the visual element with respect to the reference frame of the link. + +| `` attr | type | use | default value | description | +| --------------- | -------- | -------- | ------------------------------------- | ---------------------------------------------------------------- | +| `xyz` | `string` | optional | defaults to zero vector | Represents the **x**, **y**, **z** offset. | +| `rpy` | `string` | optional | defaults to identity if not specified | Represents the fixed axis roll, pitch and yaw angles in radians. | + +#### visual: `` + +The shape of the visual object. + +This element **may contain one** of the following elements: +| `` element | use | description | +| ---------------------------------- | -------- | --------------------------- | +| [``](#geometry-box) | optional | Defines a cubic mesh. | +| [``](#geometry-cylinder) | optional | Defines a cylindrical mesh. | +| [``](#geometry-sphere) | optional | Defines a spherical mesh. | +| [``](#geometry-mesh) | optional | Defines a custom mesh. | + +##### geometry: `` + +| `` attr | type | use | default value | description | +| ------------ | -------- | -------- | ------------- | ------------------------------------------------------------------------------------------------ | +| `size` | `string` | optional | zero vector | The three side lengths of the box in the form `"x y z"`. The origin of the box is in its center. | + +##### geometry: `` + +The origin of the cylinder is in its center. Cylinder Coordinates + +| `` attr | type | use | default value | description | +| ----------------- | -------- | -------- | ---------------- | ----------- | +| `radius` | `double` | required | Cylinder radius. | +| `length` | `double` | required | Cylinder lenght. | + +##### geometry: `` + +The origin of the sphere is in its center. + +| `` attr | type | use | default value | description | +| --------------- | -------- | -------- | ------------- | -------------- | +| `radius` | `double` | required | NA | Sphere radius. | + +##### geometry: `` + +A trimesh element specified by a **`filename`**, and an optional **`scale`** that scales the mesh's axis-aligned-bounding-box. Any geometry format is acceptable but specific application compatibility is dependent on implementation. The recommended format for best texture and color support is Collada .dae files. The mesh file is not transferred between machines referencing the same model. It must be a local file. Prefix the filename with **`package:///`** to make the path to the mesh file relative to the package ``. + +| `` attr | type | use | default value | description | +| ------------- | -------- | -------- | ------------- | ------------------------------------------------- | +| `filename` | `anyURI` | required | NA | Absolute path to the mesh file. | +| `scale` | `double` | optional | unit vector | Scale factor for the mesh in form `"x y z"` axis. | + +#### visual: `` + +The material of the visual element. It is allowed to specify a material element outside of the 'link' object, in the top level 'robot' element. From within a link element you can then reference the material by name. + +| `` attr | type | use | default value | description | +| ----------------- | -------- | -------- | ------------- | --------------------- | +| `name` | `string` | optional | none | Name of the material. | + +Child elements of a `material` element: +| `` element | use | description | +| -------------------------------- | -------- | ----------------------------------- | +| [``](#material-color) | optional | Defines the color of the material. | +| [``](#material-texture) | optional | Defines the texture of the material | + +##### material: `` + +| `` attr | type | use | default value | description | +| -------------- | -------- | -------- | ------------- | ------------------------------------------------------------------------------------------------------------------------ | +| `rgba` | `string` | optional | `"0 0 0 0"` | The color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. | + +##### material: `` + +| `` attr | type | use | default value | description | +| ---|---|----|----|----| +| `filename` | `anyURI` | required | NA | Path to rhe texture of a material. | + +### `` + +The link’s mass, position of its center of mass, and its central inertia properties. + +Child elements of a `` element: +| `` element | use | description | +| -------------------------------- | ----------------------------------------------- | -------------------------------------------------------------------------------- | +| [``](#inertial-origin) | optional: defaults to identity if not specified | This pose (translation, rotation) of the link’s center of mass w.r.t. link-frame | +| [``](#inertial-mass) | required | The mass of the link is represented by the value attribute of this element | +| [``](#inertial-inertia) | ??? | interia matrix, see [``](#inertial-inertia) element for more details. | + + + +#### inertial: `` + +(optional: defaults to identity if not specified)* + +This pose (translation, rotation) describes the position and orientation of the link’s center of mass frame C relative to the link-frame L. + +| `` attr | type | use | default value | description | +| ----------------- | -------- | -------- | ------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `xyz` | `string` | optional | defaults to zero vector | Represents the position vector from Lo (the link-frame origin) to Co (the link’s center of mass) as **x L̂x + y L̂y + z L̂z**, where **L̂x, L̂y, L̂z** are link-frame L's orthogonal unit vectors. | +| `rpy` | `string` | optional | defaults to identity if not specified | Represents the orientation of C's unit vectors **Ĉx, Ĉy, Ĉz** relative to link-frame L as a sequence of Euler rotations (r p y) in radians. *Note*: **Ĉx, Ĉy, Ĉz** do not need to be aligned with the link’s principal axes of inertia. | + +#### inertial: `` + +The mass of the link is represented by the **`value`** attribute of this element. + +#### inertial: `` + +This link's moments of inertia **ixx, iyy, izz** and products of inertia **ixy, ixz, iyz** about Co (the link’s center of mass) for the unit vectors **Ĉx, Ĉy, Ĉz** fixed in the center-of-mass frame C. Note: the orientation of **Ĉx, Ĉy, Ĉz** relative to **L̂x, L̂y, L̂z** is specified by the rpy values in the tag. The attributes **ixx, ixy, ixz, iyy, iyz, izz** for some primitive shapes are [here](https://en.wikipedia.org/wiki/List_of_moments_of_inertia#List_of_3D_inertia_tensors). URDF assumes a negative product of inertia convention (for more info, see [these MathWorks docs](https://www.mathworks.com/help/releases/R2021b/physmod/sm/ug/specify-custom-inertia.html#mw_b043ec69-835b-4ca9-8769-af2e6f1b190c) for working with CAD tools). The simplest way to avoid compatibility issues associated with the negative sign convention for product of inertia is to align **Ĉx, Ĉy, Ĉz** with principal inertia directions so that all the products of inertia are zero. + + +### `` + +The collision properties of a link. Note that this can be different from the visual properties of a link, for example, simpler collision models are often used to reduce computation time. **Note:** multiple instances of `` tags can exist for the same link. The union of the geometry they define forms the collision representation of the link. + +| `` attr | type | use | default value | description | +| ------------------ | -------- | -------- | ------------- | -------------------------------------------------------------------------------------------------------------------------------- | +| `name` | `string` | optional | none | Specifies a name for a part of a link's geometry. This is useful to be able to refer to specific bits of the geometry of a link. | + +Child elements of a `` element: +| `` element | use | description | +| --------------------- | ---------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------ | +| `` | optional: same as the [``](#visual-geometry) element in the [``](#visual) element. | The reference frame of the collision element, relative to the reference frame of the link. | +| `` | optional: same as the [``](#visual-geometry) element in the [``](#visual) element. | See the geometry description in the above [``](#visual) element. | + +## Recommended Mesh Resolution + +For collision checking using the [[moveit| ROS motion planning]] packages, as few faces per link as possible are recommended for the collision meshes that you put into the URDF (ideally less than 1000). If possible, approximating the meshes with other primitives is encouraged. + +## Multiple Collision Bodies + +It was decided that URDFs should not support multiple groups of collision bodies, even though there are sometimes applications for this. The URDF is intended to only represent the actual robot's properties, and not collisions used for external things like controller collision checking. In a URDF, the elements should be as accurate as possible to the real robot, and the elements should still be a close approximation, albeit with far fewer triangles in the meshes. + +If you do need coarser-grain, over sized collision geometries for things like collision checking and controllers, you can move these meshes/geometries to custom XML elements. For example, if your controllers need some special rough collision checking geometry, you could add the tag after the element: + +~~~xml + + + + + + + + + + + + + + + + + + + + + ... + + +~~~ + +A URDF will ignore these custom elements like "collision_checking", and your particular program can parse the XML itself to get this information. + +## Example + +Here is an example of a link element: + +~~~xml + + + + + + + + + + + + + + + + + + + + + + + + +~~~ \ No newline at end of file diff --git a/specification/link.png b/specification/link.png new file mode 100644 index 00000000..8f9fe064 Binary files /dev/null and b/specification/link.png differ diff --git a/specification/robot.md b/specification/robot.md new file mode 100644 index 00000000..c4338de7 --- /dev/null +++ b/specification/robot.md @@ -0,0 +1,27 @@ +# `` element + +The root element in a robot description file must be a `` element, with all other elements must be encapsulated within. + +## Attributes + +| `` attr | type | use | default value | description | +| -------------- | ------ | -------- | ------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `name` | string | required | NA | The master file must have a *name* attribute. The *name* attribute is optional in included files. If the attribute *name* is specified in an additional included file, it must have the same value as in the master file. | +| `version` | string | optional | "1.0" | version of the urdf specification in `.` format. | + +## Elements + +| `` element | description | +| ------------------------------------- | -------------------------------------------------------------------- | +| [``](./link.md) | defines a link with its own frame. | +| [``](./joint.md) | mandatory joint frame definition. | +| [``](./transmission.md) | (PR2 specific). | +| [``](./gazebo.md) | [Gazebo](http://wiki.ros.org/gazebo_ros_pkgs) simulation extensions. | + +## Example + +```xml + + + +``` diff --git a/specification/sensor.md b/specification/sensor.md new file mode 100644 index 00000000..71a3b920 --- /dev/null +++ b/specification/sensor.md @@ -0,0 +1,111 @@ +# `` element + +>[!WARNING] +> 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! + +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 + + + + + + + +``` + +And below is an example of a laser scan (ray) sensor element: + +```xml + + + + + + + + +``` + +## Attributes + +| attribute | type | use | default value | description | +| ------------- | -------- | -------- | ---------------------------------------------------------------------------------------------------------------------------- | --------------------------- | +| `name` | `string` | required | NA | The name of the sensor link | +| `update_rate` | `double` | optional | The frequency at which the sensor data is generated in `hz`. If left unspecified, the sensor will generate data every cycle. | + +## Elements + +| element | use | description | +| ---------------------- | -------- | -------------------------------------------------------------------------------------------- | +| [``](#origin)` | optional | This is the pose of the sensor optical frame, relative to the sensor parent reference frame. | +| [``](#camaera) | optional | Camera sensor definition. | +| [``](#ray) | optional | Laser sensor definition. | + +### `` + + +| attribute | type | use | default value | description | +| --------- | -------- | -------- | ------------- | ------------------------------------------------------- | +| `link` | `string` | required | NA | The name of the parent link this sensor is attached to. | + +### `` + +| attribute | type | use | default value | description | +| `xyz` | `string` | optional | zero vector | Represents the offset with respect to the parent frame. | +| `rpy` | `string` | optional | zero vector | Represents the fixed axis roll, pitch and yaw angles in radians. | + +### `` + +The `` element has following child elements: +| element | use | description | +| -------------------------- | -------- | ----------------------------- | +| [``](#camera-image) | required | Defines the image parameters. | + +#### camera: `` + +| attribute | type | use | default value | description | +| --------- | -------------- | -------- | ------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `width` | `unsigned int` | required | NA | Width of the camera in `pixels`. | +| `height` | `unsigned int` | required | NA | Height of the camera in `pixels`. | +| `format` | `string` | required | NA | Can be any of the strings defined in [image_encodings.h insdie sensor_msgs](https://code.ros.org/trac/ros-pkg/browser/stacks/common_msgs/trunk/sensor_msgs/include/sensor_msgs/image_encodings.h). | +| `hfov` | `double` | required | NA | Horizontal field of view of the camera in `radians`. | +| `near` | `double` | required | NA | Near clip distance of the camera in `meters`. | +| `far` | `double` | required | NA | Far clip distance of the camera in `meters`. This needs to be greater or equal to near clip. | + +### `` + +The `` element has following child elements: +| element | use | description | +| -------------- | -------- | ----------------------------------------------- | +| `` | optional | Defines the horizontal parameters of the laser. | +| `` | optional | Defines the vertical parameters of the laser. | + +#### ray: `` + +| attribute | type | use | default value | description | +| ------------ | -------------- | -------- | ------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| `samples` | `unsigned int` | optional | 1 | The number of simulated rays to generate per complete laser sweep cycle. | +| `resolution` | `unsigned int` | optional | 1 | 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` | `double` | optional | Minimun angle in `radians`. | +| `max_angle` | `double` | optional | Maximum angle in `radian`. Must be greater or equal to `min_angle`. | + +#### ray: `` + +| attribute | type | use | default value | description | +| ------------ | -------------- | -------- | ------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| `samples` | `unsigned int` | optional | 1 | The number of simulated rays to generate per complete laser sweep cycle. | +| `resolution` | `unsigned int` | optional | 1 | 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` | `double` | optional | Minimun angle in `radians`. | +| `max_angle` | `double` | optional | Maximum angle in `radian`. Must be greater or equal to `min_angle`. | + +## Recommended Camera or Ray Resolution + +In 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. + +## Proposal for New Type of Sensor + +TBD \ No newline at end of file diff --git a/xsd/urdf.xsd b/xsd/urdf.xsd index ccebfb26..130b64bd 100644 --- a/xsd/urdf.xsd +++ b/xsd/urdf.xsd @@ -13,6 +13,18 @@ xmlns="http://www.ros.org" elementFormDefault="qualified"> + + + + + + + + + + + + @@ -142,7 +154,6 @@ - @@ -270,6 +281,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -293,7 +365,7 @@ type="mimic" minOccurs="0" maxOccurs="1" /> - + @@ -314,6 +386,12 @@ type="transmission" minOccurs="0" maxOccurs="unbounded" /> + + + +