curobo.cuda_robot_model.cuda_robot_generator module

Generates a Tensor representation of kinematics for use in CudaRobotModel. This module reads the robot from a KinematicsParser and generates the necessary tensors for kinematics computation.

class CudaRobotGeneratorConfig(
base_link: str,
ee_link: str,
tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
link_names: List[str] | None = None,
collision_link_names: List[str] | None = None,
collision_spheres: None | str | Dict[str, Any] = None,
collision_sphere_buffer: float | Dict[str, float] = 0.0,
compute_jacobian: bool = False,
self_collision_buffer: Dict[str, float] | None = None,
self_collision_ignore: Dict[str, List[str]] | None = None,
debug: Dict[str, Any] | None = None,
use_global_cumul: bool = True,
asset_root_path: str = '',
mesh_link_names: List[str] | None = None,
load_link_names_with_mesh: bool = False,
urdf_path: str | None = None,
usd_path: str | None = None,
usd_robot_root: str | None = None,
isaac_usd_path: str | None = None,
use_usd_kinematics: bool = False,
usd_flip_joints: List[str] | None = None,
usd_flip_joint_limits: List[str] | None = None,
lock_joints: Dict[str, float] | None = None,
extra_links: Dict[str, LinkParams] | None = None,
add_object_link: bool = False,
use_external_assets: bool = False,
external_asset_path: str | None = None,
external_robot_configs_path: str | None = None,
extra_collision_spheres: Dict[str, int] | None = None,
cspace: None | CSpaceConfig | Dict[str, List[Any]] = None,
load_meshes: bool = False,
)

Bases: object

Robot representation generator configuration, loads from a dictionary.

Name of base link for kinematic tree.

Name of end-effector link to compute pose.

tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32)

Device to load cuda robot model.

Name of link names to compute pose in addition to ee_link.

Name of links to compute sphere positions for use in collision checking.

collision_spheres: None | str | Dict[str, Any] = None

Collision spheres that fill the volume occupied by the links of the robot. Collision spheres can be generated for robot using Isaac Sim Robot Description Editor.

collision_sphere_buffer: float | Dict[str, float] = 0.0

Radius buffer to add to collision spheres as padding.

compute_jacobian: bool = False

Compute jacobian of link poses. Currently not supported.

self_collision_buffer: Dict[str, float] | None = None

Padding to add for self collision between links. Some robots use a large padding for self collision avoidance (e.g., MoveIt Panda Issue).

self_collision_ignore: Dict[str, List[str]] | None = None

Dictionary with each key as a link name and value as a list of link names to ignore self collision. E.g., {“link1”: [“link2”, “link3”], “link2”: [“link3”, “link4”]} will ignore self collision between link1 and link2, link1 and link3, link2 and link3, link2 and link4. The mapping is bidirectional so it’s sufficient to mention the mapping in one direction (i.e., not necessary to mention “link1” in ignore list for “link2”).

debug: Dict[str, Any] | None = None

Debugging information to pass to kinematics module.

use_global_cumul: bool = True

Enabling this flag writes out the cumulative transformation matrix to global memory. This allows for reusing the cumulative matrix during backward of kinematics (15% speedup over recomputing cumul in backward).

asset_root_path: str = ''

Path of meshes of robot links. Currently not used as we represent robot link geometry with collision spheres.

Names of links to load meshes for visualization. This is only used for exporting visualizations.

Set this to true to add mesh_link_names to link_names when computing kinematics.

urdf_path: str | None = None

Path to load robot urdf.

usd_path: str | None = None

Path to load robot usd.

usd_robot_root: str | None = None

Root prim of robot in usd.

isaac_usd_path: str | None = None

Path of robot in Isaac server.

use_usd_kinematics: bool = False

Load Kinematics chain from usd.

usd_flip_joints: List[str] | None = None

Joints to flip axis when loading from USD

usd_flip_joint_limits: List[str] | None = None

Flip joint limits in USD.

lock_joints: Dict[str, float] | None = None

Lock active joints in the kinematic tree. This will convert the joint to a fixed joint with joint angle given from this dictionary.

Additional links to add to parsed kinematics tree. This is useful for adding fixed links that are not present in the URDF or USD.

Deprecated way to add a fixed link.

use_external_assets: bool = False

Deprecated flag to load assets from external module. Now, pass absolute path to asset_root_path or use ContentPath.

external_asset_path: str | None = None

Deprecated path to load assets from external module. Use ContentPath instead.

external_robot_configs_path: str | None = None

Deprecated path to load robot configs from external module. Use ContentPath instead.

extra_collision_spheres: Dict[str, int] | None = None

Create n collision spheres for links with name

cspace: None | CSpaceConfig | Dict[str, List[Any]] = None

Configuration space parameters for robot (e.g, acceleration, jerk limits).

load_meshes: bool = False

Enable loading meshes from kinematics parser.

class CudaRobotGenerator(
config: CudaRobotGeneratorConfig,
)

Bases: CudaRobotGeneratorConfig

Robot Kinematics Representation Generator.

The word “Chain” is used interchangeably with “Tree” in this class.

Initialize the robot generator.

Parameters:

config – Parameters to initialize the robot generator.

property kinematics_config: KinematicsTensorConfig

Kinematics representation as Tensors.

property self_collision_config: SelfCollisionKinematicsConfig

Self collision configuration for robot.

property kinematics_parser

Kinematics parser used to generate robot parameters.

initialize_tensors()

Initialize tensors for kinematics representatiobn.

Add an extra link to the robot kinematics tree.

Parameters:

link_params – Parameters of the link to add.

Add a fixed link to the robot kinematics tree.

Parameters:
  • link_name – Name of the link to add.

  • parent_link_name – Parent link to add the fixed link to.

  • joint_name – Name of fixed to joint to create.

  • transform – Offset transform of the fixed link from the joint.

_build_chain(
base_link: str,
ee_link: str,
other_links: List[str],
) List[str]

Build kinematic tree of the robot.

Parameters:
  • base_link – Name of base link for the chain.

  • ee_link – Name of end-effector link for the chain.

  • other_links – List of other links to add to the chain.

Returns:

List of link names in the chain.

Return type:

List[str]

_get_mimic_joint_data() Dict[str, List[int]]

Get joints that are mimicked from actuated joints joints.

Returns:

Dictionary containing name of actuated joint and list of mimic

joint indices.

Return type:

Dict[str, List[int]]

_build_kinematics_tensors(
base_link,
link_names,
chain_link_names,
)

Create kinematic tensors for robot given kinematic tree.

Parameters:
  • base_link – Name of base link for the tree.

  • link_names – Namer of links to compute kinematics for. This is used to determine link indices to store pose during forward kinematics.

  • chain_link_names – List of link names in the kinematic tree. Used to traverse the kinematic tree.

_build_kinematics(
base_link: str,
ee_link: str,
other_links: List[str],
link_names: List[str],
)

Build kinematics tensors given base link, end-effector link and other links.

Parameters:
  • base_link – Name of base link for the kinematic tree.

  • ee_link – Name of end-effector link for the kinematic tree.

  • other_links – List of other links to add to the kinematic tree.

  • link_names – List of link names to store poses after kinematics computation.

_build_kinematics_with_lock_joints(
base_link: str,
ee_link: str,
other_links: List[str],
link_names: List[str],
lock_joints: Dict[str, float],
)

Build kinematics with locked joints.

This function will first build the chain with no locked joints, find the transforms when the locked joints are set to the given values, and then use these transforms as fixed transforms for the locked joints.

Parameters:
  • base_link – Base link of the kinematic tree.

  • ee_link – End-effector link of the kinematic tree.

  • other_links – Other links to add to the kinematic tree.

  • link_names – List of link names to store poses after kinematics computation.

  • lock_joints – Joints to lock in the kinematic tree with value to lock at.

_build_collision_model(
collision_spheres: Dict,
collision_link_names: List[str],
collision_sphere_buffer: float | Dict[str, float] = 0.0,
)

Build collision model for robot.

Parameters:
  • collision_spheres – Spheres for each link of the robot.

  • collision_link_names – Name of links to load spheres for.

  • collision_sphere_buffer – Additional padding to add to collision spheres.

_create_self_collision_thread_data(
collision_threshold: Tensor,
) Tuple[Tensor, int, bool, int]

Create thread data for self collision checks.

Parameters:

collision_threshold – Collision distance between spheres of the robot. Used to skip self collision checks when distance is -inf.

Returns:

Thread location for self collision checks,

number of self collision checks, if thread calculation was successful, and number of checks per thread.

Return type:

Tuple[torch.Tensor, int, bool, int]

_add_body_to_tree(
link_name: str,
base=False,
)

Add link to kinematic tree.

Parameters:
  • link_name – Name of the link to add.

  • base – Is this the base link of the kinematic tree?

Get data (parent link, child link, mimic, link_index) for joints given in the list.

Parameters:

joint_names – Names of joints to get data for.

Returns:

Dictionary containing joint name as key and

dictionary containing parent link, child link, and link index as values. Also includes mimic joint data if present.

Return type:

Dict[str, Dict[str, Union[str, int]]]

Get Pose of links at given joint angles using forward kinematics.

This is implemented here to avoid circular dependencies with CudaRobotModel module. This is used to calculate fixed transforms for locked joints in this class. This implementation does not compute position of robot spheres.

Parameters:
  • q – Joint angles to compute forward kinematics for.

  • link_names – Name of links to return pose.

  • kinematics_config – Tensor Configuration for kinematics computation.

Returns:

Pose of links at given joint angles.

Return type:

Pose

get_joint_limits() JointLimits

Get joint limits for the robot.

_get_joint_position_velocity_limits() Dict[str, Tensor]

Compute joint position and velocity limits for the robot.

Returns:

Dictionary containing position and velocity limits for the

robot. Each value is a tensor of shape (2, n_joints) with first row containing minimum limits and second row containing maximum limits.

Return type:

Dict[str, torch.Tensor]

_update_joint_limits()

Update limits from CSpaceConfig (acceleration, jerk limits and position clips).

Deprecated way to add a fixed link.

asset_root_path: str = ''

Path of meshes of robot links. Currently not used as we represent robot link geometry with collision spheres.

Name of links to compute sphere positions for use in collision checking.

collision_sphere_buffer: float | Dict[str, float] = 0.0

Radius buffer to add to collision spheres as padding.

collision_spheres: None | str | Dict[str, Any] = None

Collision spheres that fill the volume occupied by the links of the robot. Collision spheres can be generated for robot using Isaac Sim Robot Description Editor.

compute_jacobian: bool = False

Compute jacobian of link poses. Currently not supported.

cspace: None | CSpaceConfig | Dict[str, List[Any]] = None

Configuration space parameters for robot (e.g, acceleration, jerk limits).

debug: Dict[str, Any] | None = None

Debugging information to pass to kinematics module.

external_asset_path: str | None = None

Deprecated path to load assets from external module. Use ContentPath instead.

external_robot_configs_path: str | None = None

Deprecated path to load robot configs from external module. Use ContentPath instead.

extra_collision_spheres: Dict[str, int] | None = None

Create n collision spheres for links with name

Additional links to add to parsed kinematics tree. This is useful for adding fixed links that are not present in the URDF or USD.

isaac_usd_path: str | None = None

Path of robot in Isaac server.

Name of link names to compute pose in addition to ee_link.

Set this to true to add mesh_link_names to link_names when computing kinematics.

load_meshes: bool = False

Enable loading meshes from kinematics parser.

lock_joints: Dict[str, float] | None = None

Lock active joints in the kinematic tree. This will convert the joint to a fixed joint with joint angle given from this dictionary.

Names of links to load meshes for visualization. This is only used for exporting visualizations.

self_collision_buffer: Dict[str, float] | None = None

Padding to add for self collision between links. Some robots use a large padding for self collision avoidance (e.g., MoveIt Panda Issue).

self_collision_ignore: Dict[str, List[str]] | None = None

Dictionary with each key as a link name and value as a list of link names to ignore self collision. E.g., {“link1”: [“link2”, “link3”], “link2”: [“link3”, “link4”]} will ignore self collision between link1 and link2, link1 and link3, link2 and link3, link2 and link4. The mapping is bidirectional so it’s sufficient to mention the mapping in one direction (i.e., not necessary to mention “link1” in ignore list for “link2”).

tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32)

Device to load cuda robot model.

urdf_path: str | None = None

Path to load robot urdf.

usd_flip_joint_limits: List[str] | None = None

Flip joint limits in USD.

usd_flip_joints: List[str] | None = None

Joints to flip axis when loading from USD

usd_path: str | None = None

Path to load robot usd.

usd_robot_root: str | None = None

Root prim of robot in usd.

use_external_assets: bool = False

Deprecated flag to load assets from external module. Now, pass absolute path to asset_root_path or use ContentPath.

use_global_cumul: bool = True

Enabling this flag writes out the cumulative transformation matrix to global memory. This allows for reusing the cumulative matrix during backward of kinematics (15% speedup over recomputing cumul in backward).

use_usd_kinematics: bool = False

Load Kinematics chain from usd.

Name of base link for kinematic tree.

Name of end-effector link to compute pose.