curobo.cuda_robot_model.cuda_robot_generator module

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

Create Cuda Robot Model Configuration.

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 https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/advanced_tutorials/tutorial_motion_generation_robot_description_editor.html#collision-spheres

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 (https://github.com/ros-planning/panda_moveit_config/pull/35#issuecomment-671333863)

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

Self-collision ignore

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

debug config

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.

this is deprecated

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

Create n collision spheres for links with name

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

cspace config

load_meshes: bool = False

Enable loading meshes from kinematics parser.

class CudaRobotGenerator(
config: CudaRobotGeneratorConfig,
)

Bases: CudaRobotGeneratorConfig

property kinematics_config
property self_collision_config
property kinematics_parser
initialize_tensors()
_build_chain(
base_link,
ee_link,
other_links,
link_names,
)
_get_mimic_joint_data()
_build_kinematics_tensors(
base_link,
ee_link,
link_names,
chain_link_names,
)
_build_kinematics(
base_link,
ee_link,
other_links,
link_names,
)
_build_kinematics_with_lock_joints(
base_link,
ee_link,
other_links,
link_names,
lock_joints: Dict[str, float],
)
_build_collision_model(
collision_spheres: Dict,
collision_link_names: List[str],
collision_sphere_buffer: float | Dict[str, float] = 0.0,
)
Parameters:
  • collision_spheres (_type_) – _description_

  • collision_link_names (_type_) – _description_

  • collision_sphere_buffer (float, optional) – _description_. Defaults to 0.0.

_create_self_collision_thread_data(
collision_threshold,
)
_add_body_to_tree(
link_name,
base=False,
)
property get_joint_limits
_get_joint_position_velocity_limits()
_update_joint_limits()

this is deprecated

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 https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/advanced_tutorials/tutorial_motion_generation_robot_description_editor.html#collision-spheres

compute_jacobian: bool = False

Compute jacobian of link poses. Currently not supported.

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

cspace config

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

debug config

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

Create n collision spheres for links with name

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 (https://github.com/ros-planning/panda_moveit_config/pull/35#issuecomment-671333863)

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

Self-collision ignore

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
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.