pycram.robot_description

Contents

pycram.robot_description#

Classes#

RobotDescriptionManager

Singleton class to manage multiple robot descriptions. Stores all robot descriptions and loads a robot description

RobotDescription

Base class of a robot description. Contains all necessary information about a robot, like the URDF, the base link,

KinematicChainDescription

Represents a kinematic chain of a robot. A Kinematic chain is a chain of links and joints that are connected to each

CameraDescription

Represents a camera mounted on a robot. Contains all necessary information about the camera, like the link name,

EndEffectorDescription

Describes an end effector of robot. Contains all necessary information about the end effector, like the

Functions#

create_manipulator_description(→ RobotDescription)

Create a robot description from a ManipulatorData object.

Module Contents#

class pycram.robot_description.RobotDescriptionManager#

Singleton class to manage multiple robot descriptions. Stores all robot descriptions and loads a robot description according to the name of the loaded robot.

_instance = None#
descriptions: typing_extensions.Dict[str, RobotDescription]#
_initialized = True#
load_description(name: str)#

Loads a robot description according to the name of the robot. This required that a robot description with the corresponding name is registered.

Parameters:

name – Name of the robot to which the description should be loaded.

Returns:

The loaded robot description.

register_description(description: RobotDescription)#

Register a robot description to the RobotDescriptionManager. The description is stored with the name of the description as key. This will later be used to load the description.

Parameters:

description – RobotDescription to register.

static register_all_descriptions()#
class pycram.robot_description.RobotDescription(name: str, base_link: str, torso_link: str, torso_joint: str, urdf_path: str, virtual_mobile_base_joints: typing_extensions.Optional[pycram.datastructures.dataclasses.VirtualMobileBaseJoints] = None, mjcf_path: typing_extensions.Optional[str] = None, ignore_joints: typing_extensions.Optional[typing_extensions.List[str]] = None, gripper_name: typing_extensions.Optional[str] = None)#

Base class of a robot description. Contains all necessary information about a robot, like the URDF, the base link, the torso link and joint, the kinematic chains and cameras.

current_robot_description: RobotDescription = None#

The currently loaded robot description.

name: str#

Name of the robot

Base link of the robot

Torso link of the robot

torso_joint: str#

Torso joint of the robot

urdf_object: pycram.object_descriptors.urdf.ObjectDescription#

Parsed URDF of the robot

kinematic_chains: typing_extensions.Dict[str, KinematicChainDescription]#

All kinematic chains defined for this robot

cameras: typing_extensions.Dict[str, CameraDescription]#

All cameras defined for this robot

All links defined in the URDF

joints: typing_extensions.List[str]#

All joints defined in the URDF, by default fixed joints are not included

virtual_mobile_base_joints: typing_extensions.Optional[pycram.datastructures.dataclasses.VirtualMobileBaseJoints] = None#

Virtual mobile base joint names for mobile robots, these joints are not part of the URDF, however they are used to move the robot in the simulation (e.g. set_pose for the robot would actually move these joints)

gripper_name: typing_extensions.Optional[str] = None#

Name of the gripper of the robot if it has one, this is used when the gripper is a different Object with its own description file outside the robot description file.

neck: typing_extensions.Dict[str, typing_extensions.List[str]]#

Dictionary of neck links and joints. Keys are yaw, pitch and roll, values are [link, joint]

ignore_joints = []#
joint_types#
joint_actuators: typing_extensions.Optional[typing_extensions.Dict]#
add_arm(end_link: str, arm_type: pycram.datastructures.enums.Arms = Arms.RIGHT, arm_name: str = 'manipulator', arm_home_values: typing_extensions.Optional[typing_extensions.Dict[str, float]] = None, arm_start: typing_extensions.Optional[str] = None) KinematicChainDescription#

Creates and adds an arm to the RobotDescription.

Parameters:
  • end_link – Last link of the arm

  • arm_type – Type of the arm

  • arm_name – Name of the arm

  • arm_home_values – Dictionary of joint names and their home values (default configuration) (e.g. park arms)

  • arm_start – Start link of the arm

property has_actuators#

Property to check if the robot has actuators defined in the MJCF file.

Returns:

True if the robot has actuators, False otherwise

get_actuator_for_joint(joint: str) typing_extensions.Optional[str]#

Get the actuator name for a given joint.

Parameters:

joint – Name of the joint

Returns:

Name of the actuator

add_kinematic_chain_description(chain: KinematicChainDescription)#

Adds a KinematicChainDescription object to the RobotDescription. The chain is stored with the name of the chain as key.

Parameters:

chain – KinematicChainDescription object to add

add_kinematic_chain(name: str, start_link: str, end_link: str)#

Creates and adds a KinematicChainDescription object to the RobotDescription.

Parameters:
  • name – Name of the KinematicChainDescription object

  • start_link – First link of the chain

  • end_link – Last link of the chain

add_camera_description(camera: CameraDescription)#

Adds a CameraDescription object to the RobotDescription. The camera is stored with the name of the camera as key. :param camera: The CameraDescription object to add

add_camera(name: str, camera_link: str, minimal_height: float, maximal_height: float)#

Creates and adds a CameraDescription object to the RobotDescription. Minimal and maximal height of the camera are relevant if the robot has a moveable torso or the camera is mounted on a moveable part of the robot. Otherwise both values can be the same.

Parameters:
  • name – Name of the CameraDescription object

  • camera_link – Link of the camera in the URDF

  • minimal_height – Minimal height of the camera

  • maximal_height – Maximal height of the camera

Returns:

get_manipulator_chains() typing_extensions.List[KinematicChainDescription]#

Get a list of all manipulator chains of the robot which posses an end effector.

Returns:

A list of KinematicChainDescription objects

get_camera_frame(robot_object_name: str = None) str#

Quick method to get the name of a link of a camera. Uses the first camera in the list of cameras.

Returns:

A name of the link of a camera

Quick method to get the name of a link of a camera. Uses the first camera in the list of cameras.

Returns:

A name of the link of a camera

get_default_camera() CameraDescription#

Get the first camera in the list of cameras.

Returns:

A CameraDescription object

get_static_joint_chain(kinematic_chain_name: str, configuration_name: typing_extensions.Union[str, enum.Enum])#

Get the static joint states of a kinematic chain for a specific configuration. When trying to access one of the robot arms the function :func: get_arm_chain should be used.

Parameters:
  • kinematic_chain_name

  • configuration_name

Returns:

get_offset(name: str) typing_extensions.Optional[pycram.datastructures.pose.PoseStamped]#

Returns the offset of a Joint in the URDF.

Parameters:

name – The name of the Joint for which the offset will be returned.

Returns:

The offset of the Joint

get_parent(name: str) str#

Get the parent of a link or joint in the URDF. Always returns the imeadiate parent, for a link this is a joint and vice versa.

Parameters:

name – Name of the link or joint in the URDF

Returns:

Name of the parent link or joint

get_child(name: str, return_multiple_children: bool = False) typing_extensions.Union[str, typing_extensions.List[str]]#

Get the child of a link or joint in the URDF. Always returns the immediate child, for a link this is a joint and vice versa. Since a link can have multiple children, the return_multiple_children parameter can be set to True to get a list of all children.

Parameters:
  • name – Name of the link or joint in the URDF

  • return_multiple_children – If True, a list of all children is returned

Returns:

Name of the child link or joint or a list of all children

get_arm_tool_frame(arm: pycram.datastructures.enums.Arms) str#

Get the name of the tool frame of a specific arm.

Parameters:

arm – Arm for which the tool frame should be returned

Returns:

The name of the link of the tool frame in the URDF.

get_arm_chain(arm: pycram.datastructures.enums.Arms) typing_extensions.Union[KinematicChainDescription, typing_extensions.List[KinematicChainDescription]]#

Get the kinematic chain of a specific arm. If the arm is set to BOTH, all kinematic chains are returned.

Parameters:

arm – Arm for which the chain should be returned

Returns:

KinematicChainDescription object of the arm

set_neck(yaw_joint: typing_extensions.Optional[str] = None, pitch_joint: typing_extensions.Optional[str] = None, roll_joint: typing_extensions.Optional[str] = None)#

Defines the neck configuration of the robot by setting the yaw, pitch, and roll joints along with their corresponding links.

Parameters:
  • yaw_joint – The joint name for the yaw movement of the neck.

  • pitch_joint – The joint name for the pitch movement of the neck.

  • roll_joint – The joint name for the roll movement of the neck.

get_neck() typing_extensions.Dict[str, typing_extensions.List[typing_extensions.Optional[str]]]#

Retrieves the neck configuration of the robot, including links and joints for yaw, pitch, and roll.

Returns:

A dictionary containing the neck configuration. Keys are yaw, pitch, and roll. Values are [link, joint].

load()#

Loads the robot description in the robot description manager, can be overridden to take more parameter into account.

unload()#

Unloads the robot description in the robot description manager, can be overridden to take more parameter into account.

class pycram.robot_description.KinematicChainDescription(name: str, start_link: str, end_link: str, urdf_object: pycram.object_descriptors.urdf.ObjectDescription, arm_type: pycram.datastructures.enums.Arms = None, include_fixed_joints=False)#

Represents a kinematic chain of a robot. A Kinematic chain is a chain of links and joints that are connected to each other and can be moved.

This class contains all necessary information about the chain, like the start and end link, the URDF object and the joints of the chain.

name: str#

Name of the chain

First link of the chain

Last link of the chain

urdf_object: pycram.object_descriptors.urdf.ObjectDescription#

Parsed URDF of the robot

include_fixed_joints: bool#

If True, fixed joints are included in the chain

List of all links in the chain

joint_names: typing_extensions.List[str]#

List of all joints in the chain

end_effector: EndEffectorDescription#

End effector of the chain, if there is one

arm_type: pycram.datastructures.enums.Arms#

Type of the arm, if the chain is an arm

static_joint_states: typing_extensions.Dict[typing_extensions.Union[str, enum.Enum], typing_extensions.Dict[str, float]]#

Dictionary of static joint states for the chain

Initializes the links of the chain by getting the chain from the URDF object.

_init_joints()#

Initializes the joints of the chain by getting the chain from the URDF object.

create_end_effector(name: str, tool_frame, opened_joint_values: typing_extensions.Dict[str, float], closed_joint_values: typing_extensions.Dict[str, float], relative_dir: typing_extensions.Optional[str] = None, resources_dir: typing_extensions.Optional[str] = None, description_name: str = 'gripper', opening_distance: typing_extensions.Optional[float] = None) EndEffectorDescription#

Create a gripper end effector description.

Parameters:
  • name – The name of the gripper.

  • tool_frame – The name of the tool frame.

  • opened_joint_values – The joint values when the gripper is open.

  • closed_joint_values – The joint values when the gripper is closed.

  • relative_dir – The relative directory of the gripper in the Multiverse resources/robots directory.

  • resources_dir – The path to the resources directory.

  • description_name – The name of the gripper description.

  • opening_distance – The openning distance of the gripper.

Returns:

The gripper end effector description.

get_joints() typing_extensions.List[str]#

Get a list of all joints of the chain.

Returns:

List of joint names

Returns:

A list of all links of the chain.

Property to get the links of the chain.

Returns:

List of link names

property joints: typing_extensions.List[str]#

Property to get the joints of the chain.

Returns:

List of joint names

add_static_joint_states(name: typing_extensions.Union[str, enum.Enum], states: dict)#

Adds static joint states to the chain. These define a specific configuration of the chain.

Parameters:
  • name – Name of the static joint states

  • states – Dictionary of joint names and their values

get_static_joint_states(name: typing_extensions.Union[str, enum.Enum]) typing_extensions.Dict[str, float]#

Get the dictionary of static joint states for a given name of the static joint states.

Parameters:

name – Name of the static joint states

Returns:

Dictionary of joint names and their values

get_tool_frame() str#

Get the name of the tool frame of the end effector of this chain, if it has an end effector.

Returns:

The name of the link of the tool frame in the URDF.

get_static_gripper_state(state: pycram.datastructures.enums.GripperState) typing_extensions.Dict[str, float]#

Get the static joint states for the gripper of the chain.

Parameters:

state – Name of the static joint states

Returns:

Dictionary of joint names and their values

class pycram.robot_description.CameraDescription(name: str, link_name: str, minimal_height: float, maximal_height: float, horizontal_angle: float = 20, vertical_angle: float = 20, front_facing_axis: typing_extensions.List[float] = None)#

Represents a camera mounted on a robot. Contains all necessary information about the camera, like the link name, minimal and maximal height, horizontal and vertical angle and the front facing axis.

name: str#

Name of the camera

Name of the link in the URDF

minimal_height: float#

Minimal height the camera can be at

maximal_height: float#

Maximal height the camera can be at

horizontal_angle: float#

Horizontal opening angle of the camera

vertical_angle: float#

Vertical opening angle of the camera

front_facing_axis: typing_extensions.List[int]#

Axis along which the camera is taking the image

class pycram.robot_description.EndEffectorDescription(name: str, start_link: str, tool_frame: str, urdf_object: pycram.object_descriptors.urdf.ObjectDescription, gripper_object_name: typing_extensions.Optional[str] = None, opening_distance: typing_extensions.Optional[float] = None, fingers_link_names: typing_extensions.Optional[typing_extensions.List[str]] = None)#

Describes an end effector of robot. Contains all necessary information about the end effector, like the base link, the tool frame, the URDF object and the static joint states.

name: str#

Name of the end effector

Root link of the end effector, every link below this link in the URDF is part of the end effector

tool_frame: str#

Name of the tool frame link in the URDf

urdf_object: pycram.object_descriptors.urdf.ObjectDescription#

Parsed URDF of the robot

List of all links in the end effector

joint_names: typing_extensions.List[str]#

List of all joints in the end effector

static_joint_states: typing_extensions.Dict[pycram.datastructures.enums.GripperState, typing_extensions.Dict[str, float]]#

Dictionary of static joint states for the end effector

end_effector_type: pycram.datastructures.enums.GripperType#

Type of the gripper

opening_distance: float#

Distance the gripper can open, in cm

gripper_object_name: typing_extensions.Optional[str] = None#

Name of the gripper of the robot if it has one, this is used when the gripper is a different Object with its own description file outside the robot description file.

List of all links of the fingers of the gripper

grasps: typing_extensions.Dict[pycram.datastructures.pose.GraspDescription, typing_extensions.List[float]]#

Dictionary of all grasp orientations of the end effector

approach_axis: typing_extensions.List[float]#

Relative axis along which the end effector is approaching an object

Traverses the URDF object to get all links and joints of the end effector below the start link.1

add_static_joint_states(name: pycram.datastructures.enums.GripperState, states: dict)#

Adds static joint states to the end effector. These define a specific configuration of the end effector. Like open and close configurations of a gripper.

Parameters:
  • name – Name of the static joint states

  • states – Dictionary of joint names and their values

Property to get the links of the chain.

Returns:

List of link names

property joints: typing_extensions.List[str]#

Property to get the joints of the chain.

Returns:

List of joint names

update_all_grasp_orientations(front_orientation: typing_extensions.List[float])#

Generates all grasp quaternion orientations based on a given front-facing quaternion orientation in-place, covering combinations of side grasps (front, back, left, right), top/bottom grasps, and horizontal rotation options.

Parameters:

front_orientation – A quaternion representing the front-facing orientation as [x, y, z, w] quaternion.

get_grasp(approach_direction: pycram.datastructures.enums.Grasp, vertical_alignment: pycram.datastructures.enums.Grasp = None, rotate_gripper: bool = False) typing_extensions.List[float]#

Retrieves the quaternion orientation of the end effector for a specific grasp.

Parameters:
  • approach_direction – The approach direction of the end effector.

  • vertical_alignment – The vertical alignment of the end effector.

  • rotate_gripper – True, the gripper should be rotated 90°.

Returns:

List of floats representing the quaternion orientation of the end effector

set_approach_axis(axis: typing_extensions.List[float])#

Sets the approach axis for the robot’s palm.

Parameters:

axis – A list representing the approach axis.

get_approach_axis() typing_extensions.List[float]#

Retrieves the approach axis.

Returns:

A list representing the approach axis.

pycram.robot_description.create_manipulator_description(data: pycram.datastructures.dataclasses.ManipulatorData, urdf_filename: str, mjcf_filename: typing_extensions.Optional[str] = None) RobotDescription#

Create a robot description from a ManipulatorData object.

Parameters:
  • data – ManipulatorData object containing all necessary information about the manipulator.

  • urdf_filename – Path to the URDF file of the robot.

  • mjcf_filename – Path to the MJCF file of the robot.

Returns:

A RobotDescription object