curobo.cuda_robot_model.cuda_robot_model module
- class CudaRobotModelConfig(
- tensor_args: 'TensorDeviceType',
- link_names: 'List[str]',
- kinematics_config: 'KinematicsTensorConfig',
- self_collision_config: 'Optional[SelfCollisionKinematicsConfig]' = None,
- kinematics_parser: 'Optional[KinematicsParser]' = None,
- compute_jacobian: 'bool' = False,
- use_global_cumul: 'bool' = False,
- generator_config: 'Optional[CudaRobotGeneratorConfig]' = None,
Bases:
object
- tensor_args: TensorDeviceType
- kinematics_config: KinematicsTensorConfig
- self_collision_config: SelfCollisionKinematicsConfig | None = None
- kinematics_parser: KinematicsParser | None = None
- generator_config: CudaRobotGeneratorConfig | None = None
- get_joint_limits()
- static from_basic_urdf(
- urdf_path: str,
- 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),
Load a cuda robot model from only urdf. This does not support collision queries.
- Parameters:
urdf_path – Path of urdf file.
base_link – Name of base link.
ee_link – Name of end-effector link.
tensor_args – Device to load robot model. Defaults to TensorDeviceType().
- Returns:
cuda robot model configuration.
- Return type:
- static from_basic_usd(
- usd_path: str,
- usd_robot_root: str,
- 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),
Load a cuda robot model from only urdf. This does not support collision queries.
- Parameters:
urdf_path – Path of urdf file.
base_link – Name of base link.
ee_link – Name of end-effector link.
tensor_args – Device to load robot model. Defaults to TensorDeviceType().
- Returns:
cuda robot model configuration.
- Return type:
- static from_robot_yaml_file(
- file_path: str,
- ee_link: str | None = None,
- 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),
- static from_data_dict(
- data_dict: Dict[str, Any],
- 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),
- static from_config(
- config: CudaRobotGeneratorConfig,
- property cspace
- class CudaRobotModelState(
- ee_position: Tensor,
- ee_quaternion: Tensor,
- lin_jacobian: Tensor | None = None,
- ang_jacobian: Tensor | None = None,
- links_position: Tensor | None = None,
- links_quaternion: Tensor | None = None,
- link_spheres_tensor: Tensor | None = None,
- link_names: str | None = None,
Bases:
object
Dataclass that stores kinematics information.
- ee_position: Tensor
End-effector position stored as x,y,z in meters [b, 3]. End-effector is defined by
CudaRobotModel.ee_link
.
- ee_quaternion: Tensor
End-effector orientaiton stored as quaternion qw, qx, qy, qz [b,4]. End-effector is defined by
CudaRobotModel.ee_link
.
- links_position: Tensor | None = None
Position of links specified by link_names (
CudaRobotModel.link_names
).
- links_quaternion: Tensor | None = None
Quaternions of links specified by link names (
CudaRobotModel.link_names
).
- link_spheres_tensor: Tensor | None = None
Position of spheres specified by collision spheres (
CudaRobotModel.robot_spheres
) in x, y, z, r format [b,n,4].
- link_names: str | None = None
Names of links that each index in
links_position
andlinks_quaternion
corresponds to.
- class CudaRobotModel(
- config: CudaRobotModelConfig,
Bases:
CudaRobotModelConfig
CUDA Accelerated Robot Model
Currently dof is created only for links that we need to compute kinematics. E.g., for robots with many serial chains, add all links of the robot to get the correct dof. This is not an issue if you are loading collision spheres as that will cover the full geometry of the robot.
- update_batch_size(
- batch_size,
- force_update=False,
- reset_buffers=False,
- forward(
- q,
- link_name=None,
- calculate_jacobian=False,
- get_state(
- q,
- link_name=None,
- calculate_jacobian=False,
- get_robot_link_meshes()
- _cuda_forward(q)
- property all_articulated_joint_names
- get_self_collision_config() SelfCollisionKinematicsConfig
- property lock_jointstate
- get_full_js(
- js: JointState,
- get_mimic_js(
- js: JointState,
- property ee_link
- property base_link
- property robot_spheres
- update_kinematics_config(
- new_kin_config: KinematicsTensorConfig,
- property retract_config
- property cspace
- static from_basic_urdf(
- urdf_path: str,
- 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),
Load a cuda robot model from only urdf. This does not support collision queries.
- Parameters:
urdf_path – Path of urdf file.
base_link – Name of base link.
ee_link – Name of end-effector link.
tensor_args – Device to load robot model. Defaults to TensorDeviceType().
- Returns:
cuda robot model configuration.
- Return type:
- static from_basic_usd(
- usd_path: str,
- usd_robot_root: str,
- 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),
Load a cuda robot model from only urdf. This does not support collision queries.
- Parameters:
urdf_path – Path of urdf file.
base_link – Name of base link.
ee_link – Name of end-effector link.
tensor_args – Device to load robot model. Defaults to TensorDeviceType().
- Returns:
cuda robot model configuration.
- Return type:
- static from_config(
- config: CudaRobotGeneratorConfig,
- static from_data_dict(
- data_dict: Dict[str, Any],
- 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),
- static from_robot_yaml_file(
- file_path: str,
- ee_link: str | None = None,
- 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),
- generator_config: CudaRobotGeneratorConfig | None = None
- get_joint_limits()
- kinematics_parser: KinematicsParser | None = None
- self_collision_config: SelfCollisionKinematicsConfig | None = None
- tensor_args: TensorDeviceType
- kinematics_config: KinematicsTensorConfig