====== Robot Description in PyCRAM ====== The robot description assigns meaning to the physical description of a robot from the URDF. This includes manipulator chains, meaning the links and joints which are part of an arm, the camera link and predefined poses for joint chains, like for example a default parking pose for an arm. On this page we will list the parts of the robot description and explain them, for a tutorial on how to create your own robot description please look at the [[/tutorials/pycram/own_robot | tutorial]]. The robot_description file contains 6 classes: * ChainDescription * GripperDescription * InteractionDescription * ManipulatorDescription * CameraDescriptin * RobotDescription ===== Chain Description ===== This class represents a kinematic chain by saving the links and joints. This chain can for example be an arm of a robot. The parameter of the constructor along with a description and the type can be seen in the table below. ^Parameter ^ Description ^ Type ^ | name | The name of this chain. | String | | joints | All joints contained in this chain in the right order. | List | | links | All links contained in this chain in the right order. | List | | base_link| The name of the first link in the chain. | String | | static_joint_states | Static joint states for this chain, for example the joint states so the arm ends up in a parking position. The parameter is a dictionary with the name of this state as key and the joint states in a list as value. | dict[str: list[float]] | The class provides a number of methods to interact with static joint chains. These methods provide interfaces to add one or more joint chains or get a specific saved joint chain. ==== add_static_joint_chain ==== Adds a specific configuration of the joints saved in this chain. For example a static joint chain would be the default parking pose of an arm of a robot. ^Parameter ^ Description ^ Type ^ | configuration | The name for this joint chain. | String | | static_joint_states | A list of joint states this chain should archive. | List[float] | ==== add_static_joint_chains ==== This method lets you add more than one static joint chain at a time. The different static joint chains are given in a dictionary with the name of the static joint chain as key and the list of states as value. ^Parameter ^ Description ^ Type ^ | static_joint_states | A dictionary containing all static joint chains to be added. The name of the static joint chain is the key and the corresponding value is a list of all joint states. | dict{str: list[float]} | ==== get_static_joint_chain ==== This method returns a static joint chain, given the name of the static joint chain. ^Parameter ^ Description ^ Type ^ | configuration | The name of the static joint chain which should be returned. | String | ===== Gripper Description ===== This class inherits from the ChainDescrioption class and describes a gripper of a robot. This class allows you to specify more details about the gripper as well as specify joint configurations for this gripper. The constructor of this class takes a lot of additional parameter to describe the gripper however all except for the name are optional. The parameter of the constructor will be explained in the table below. ^Parameter ^ Description ^ Type ^ | name | The name of this gripper description, it doesn't have to correspond to the links of the gripper. | String | | gripper_links | A list of the names of all links belonging to this gripper in the right order. | List[String] | | gripper_joints | A list of the names of all joints belonging to this gripper in the right order. | List[String] | | static_gripper_joint_states | A dictionary containing static joint states. See also add_static_joints_chains | dict{str: list[float]} | | gripper_meter_to_jnt_multiplier | A parameter specifying the relationship between meters and the joint state value. | float | | gripper_minimal_position | The lowest value the gripper joint can be. | float | | gripper_convergence_delta | Describes the convergence delta of this gripper. | float | The GripperDescription class doesn't define any methods. However, since it inherits from the ChainDescription class all methods of the ChainDescription class are also available. ===== Interaction Description ===== This class allows to put on the end of an chain another link, which is saved as an end effector. Therefore, chains can be defined which specify the interaction frame for the robot. An example could be a storage place for grasped objects on the robot. The parameter of the constructor can be seen in the table below. chain of links: chain_description <-> eef_link ^Parameter ^ Description ^ Type ^ | chain_description | A chain description for which this interaction should be defined. | ChainDescription | | eef_link | The name of a link which should be saved as the end effector. | String | This class doesn't define any methods but since it inherits from the ChainDescription class all methods of the ChainDescription are also available. ===== Manipulator Description ===== This class allows with the given interaction description to include a gripper description which is placed between the last link of the interaction description and the rest of it. Independently from that a tool frame can be saved, which allows to use objects to manipulate the environment. |--> (tool_frame) chain of links: interaction_description <-> (gripper_description) -| |--> eef_link The parameter of the constructor will be shown in the following table. ^Parameter ^ Description ^ Type ^ | interaction_description | The interaction description for which this manipulator description should be appended. | InteractionDescription | | tool_frame | The name of a link which should be used as a tool frame for this manipulator description. This parameter is optional. | String | | gripper_description | A gripper description which should be used between the interaction description and the end effector and tool frame. This parameter is optional. | GripperDesctiption| This class doesn't define any methods but since it inherits from the InteractionDescription class all methods of the InteractionDescription are also available. ===== Camera Description ====== This class represents a camera of the robot, it saves the link in the URDF as well as additional parameter which describe physical properties of the camera. The parameter of the constructor of this class can be seen in the table below. ^Parameter ^ Description ^ Type ^ | name | The name of the link in the URDF representing the camera. | String | | minimal_height| The minimal height the camera can see. | float | | maximal_height | The maximal height the camera can see. | float | | vertical_angle | The vertical angle of the camera mount. | float | | horizontal_angle | The horizontal angle of the camera mount. | float | | other_params | Here can parameter be specified which are not mentioned before like the focal length of the camera. | dict{str: float} | This class doesn't define any methods. ===== Robot Description ===== The RobotDescription is an abstract class which needs to be inherited from to implement a robot description for a specific robot. It implements different functions to add and get chains of different objects types which inherit of the class ChainDescription. Moreover, it allows to model the robot with its odom_frame, base_frame, base_link and torso links and joints. Different cameras can be added and static transforms and poses can be added too. The parameter of the constructor can be seen in the table below. ^Parameter ^ Description ^ Type ^ | name | The name of this robot. | String | | base_frame | The link name of the base frame of this robot. | String | | base_link | The link name of the base link of this robot. | String | | torso_link | The link name of the torso of this robot. | String | | torso_joint | The name of the joint moving the torso. | String | | ik_joints | Deprecated, should not be used. | None | | odom_frame | The link name of the odom frame of this robot, can also be a list of link names. This parameter is optional. | String or List| | odom_joints | The joint name of the odom joint, if there are more than one a list can be given which has to correspond with the order of the odom_frame list | String or list | There are a number of methods defined by the RobotDescription class to add more information or retrieve saved informations about the robot. In the following we will take a close look at all methods and explain the parameter these methods take. ==== get_tool_frame ==== This method returns the saved tool frame of a manipulator description, saved by the given name. ^Parameter ^ Description ^ Type ^ | manipulator_name | The name for which the manipulator description is saved. | String | ==== get_static_joint_chain ==== Returns a static joint chain given the name of a ChainDescription and a configuration of this chain. The chain name is the name which identifies a particular chain description in the robot description. For example, 'left' for a chain description describing the left arm of a robot. ^Parameter ^ Description ^ Type ^ | chain_name | The name for which a chain description is saved in the robot description. | String | | configuration | The desired configuration saved in the chain description, this is equal to the static joint chains. | String | ==== add_chain ==== This method adds a chain description with a name identifying this chain. For example, the name is 'left' and the chain description describes the left arm of a robot. ^Parameter ^ Description ^ Type ^ | name | A name which is used for identifying the chain description. | String | | chain_description | A chain description which should be added to the robot description. | ChainDescription | ==== add_chains ==== This method lets you add more than one chain at a time by taking a dictionary composed of the name identifying the chain as key and the chain description as value. ^Parameter ^ Description ^ Type ^ | chains_dict | A dictionary containing multiple chain descriptions. | dict{str: ChainDescrition}| ==== add_camera ==== This method adds a camera description to this robot description. The method uses, like add_chain, a name to identify the camera description. ^Parameter ^ Description ^ Type ^ | name | The name which should identify the camera. | String | | camera_description | A camera description which should be added under the given name. | CameraDescription | ==== add_cameras ==== This method lets you add more than one camera at a time by taking a dictionary containing multiple camera descriptions. The key of the dictionary functions as the name to identify the camera description in the corresponding value. ^Parameter ^ Description ^ Type ^ | cameras_dict | A dictionary containing multiple camera descriptions. | dict{str: CameraDescription} ==== get_camera_frame ==== Returns the camera frame for a given name of a camera description. ^Parameter ^ Description ^ Type ^ | camera_name | The name of the camera description for which the frame should be returned. | String | ==== add_static_joint_chain ==== This method adds a static joint chain to a chain description saved in this robot description. See also add_static_joint_chain of the ChainDescription above. ^Parameter ^ Description ^ Type ^ | chain_name | The name used to identify the chain description | String | | configuration | The name of the configuration which should be added. | String | | static_joint_states | The joint states used in this configuration. | list[float] | ==== add_static_joint_chains ==== This method allows you to add multiple static joint chains at once. See also add_static_joint_chains of the ChainDescription above. ^Parameter ^ Description ^ Type ^ | chain_name | The name used to identify the chain description | String | | static_joint_states | A dictionary containing the static joint chains. | dict{str: list[float]} | ==== add_static_gripper_chain ==== This method adds a static joint chain to a saved manipulator description. The static joint chain is meant to be used for the gripper. ^Parameter ^ Description ^ Type ^ | manipulator_name | The name used to identify the manipulator description in the robot description. | String | | configuration | A name describing the configuration of this static joint chain. | String | | static_joint_states | A list of joint states. | list[float] | ==== add_static_gripper_chains ==== This method adds more than one static joint chain to a manipulator description. ^Parameter ^ Description ^ Type ^ | manipulator_name | The name used to identify the manipulator description in the robot description. | String | | static_joint_states | A dictionary containing the static joint chains. | dict{str: list[float]} | ==== get_static_gripper_chain ==== Returns a static gripper joint chain for a given manipulator description and configuration. ^Parameter ^ Description ^ Type ^ | manipulator_name | The name used to identify the manipulator description in the robot description. | String | | configuration | The name of the desired configuration in the given manipulator description. | String |