[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

robot_model: collada_parser | collada_urdf | colladadom | convex_decomposition | ivcon | kdl_parser | resource_retriever | robot_state_publisher | simmechanics_to_urdf | srdf | urdf | urdf_interface | urdf_parser

Package Summary

SRDF (Semantic Robot Description Format) is a representation of semantic information about robots.

robot_model: angles | assimp | collada-dom | collada_parser | collada_urdf | common_msgs | convex_decomposition | curl | geometry | graphviz | ivcon | kdl_parser | orocos_kdl | resource_retriever | robot_state_publisher | ros | ros_comm | rosconsole_bridge | srdf | urdf | urdf_interface | urdf_parser | urdfdom | urdfdom_headers

Package Summary

SRDF (Semantic Robot Description Format) is a representation of semantic information about robots.

Semantic Robot Description Format (SRDF)

Proposer: Sachin Chitta, Kaijen Hsiao, Gil Jones, Ioan Sucan, John Hsu

This format is intended to represent information about the robot that is not in the URDF file, but it is useful for a variety of applications. The intention is to include information that has a semantic aspect to it. A review of this format is available here.

Description

Tags

Generic Example

<?xml version="1.0"?>

 <!-- This does not replace URDF, and is not an extension of URDF.
      This is a format for representing semantic information about the robot structure.
      A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined -->
 <robot name="some robot">

   <group name="group1">
      <!-- when a link is specified, the parent joint of that link (if it exists) is automatically included -->
      <link name="..."/>
      <link name="..."/>

      <!-- when a joint is specified, the child link of that joint (which will always exist) is automatically included -->
      <joint name="..." />

      <!-- when a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group -->
      <chain base_link="l_shoulder_pan_link" tip_link="l_wrist_roll_link"/>
      <chain base_link="r_shoulder_pan_link" tip_link="r_wrist_roll_link"/>
   </group>

   <!-- groups can also be formed by referencing to already defined group names -->
   <group name="arms">
      <group name="left_arm"/>
      <group name="right_arm"/>
      <link name="..." />
   </group>

   <!-- define a named state/configuration of a group -->
   <group_state name="name of this state" group="name of group the state is for">
      <joint name="name of joint in group" value="" />
      <!-- all joints must be specified for the state to be valid -->
   </group_state>

   <!-- Define how the robot moves in its environment, i.e., connection to robot's root link -->
   <virtual_joint name="world_joint" type="planar" parent_frame="some fixed frame" child_link="robot's root link name"/> <!-- type can be planar, floating or fixed -->

   <!-- We can then include the virtual joint in groups -->
   <group name="whole_body">
      <group name="arms"/>
      <joint name="world_joint"/>
   </group>


   <!-- define end effectors -->
   <end_effector name="some diff name" parent_link="..." group="group_name"/>

   <!-- By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. There can be many such tags in this file.-->
   <disable_collisions link1="link1" link2="link2" />

</robot>

Example for the PR2

<?xml version="1.0"?>

<robot name="pr2">

   <virtual_joint name="world_joint" type="planar" parent_frame="odom" child_link="base_footprint"/>

   <group name="right_arm">
      <chain base_link="torso_lift_link" tip_link="r_wrist_roll_link"/>
   </group>

   <group name="left_arm">
      <chain base_link="torso_lift_link" tip_link="l_wrist_roll_link"/>
   </group>

   <group name="arms">
      <group name="left_arm"/>
      <group name="right_arm"/>
   </group>

   <group_state name="tuck_arms" group="arms">
      <joint name="l_shoulder_pan_joint" value="0.2" />
      <!-- ... the rest of the joint values... -->
   </group_state>

   <group name="base">
      <joint name="world_joint"/>
   </group>

   <group name="whole_body">
      <group name="arms"/>
      <group name="base"/>
      <joint name="torso_lift_joint"/>
   </group>

   <group name="l_end_effector">
      <joint name="l_gripper_palm_joint" />
      <joint name="l_gripper_l_finger_joint" />
      <joint name="l_gripper_l_finger_tip_joint" />
      <joint name="l_gripper_led_joint" />
      <joint name="l_gripper_motor_accelerometer_joint" />
      <joint name="l_gripper_motor_slider_joint" />
      <joint name="l_gripper_motor_screw_joint" />
      <joint name="l_gripper_r_finger_joint" />
      <joint name="l_gripper_r_finger_tip_joint" />
      <joint name="l_gripper_joint" />
      <joint name="l_gripper_tool_joint" />
   </group>

   <group name="r_end_effector">
      <joint name="r_gripper_palm_joint" />
      <joint name="r_gripper_l_finger_joint" />
      <joint name="r_gripper_l_finger_tip_joint" />
      <joint name="r_gripper_led_joint" />
      <joint name="r_gripper_motor_accelerometer_joint" />
      <joint name="r_gripper_motor_slider_joint" />
      <joint name="r_gripper_motor_screw_joint" />
      <joint name="r_gripper_r_finger_joint" />
      <joint name="r_gripper_r_finger_tip_joint" />
      <joint name="r_gripper_joint" />
      <joint name="r_gripper_tool_joint" />
   </group>

   <end_effector name="r_end_effector" parent_link="r_wrist_roll_link" group="r_end_effector"/>
   <end_effector name="l_end_effector" parent_link="l_wrist_roll_link" group="l_end_effector"/>

   <disable_collisions link1="r_shoulder_pan_link" link2="r_shoulder_lift_link" />
   <!-- and many more disable_collisions tags -->

</robot>

2024-03-23 13:01