curobo.cuda_robot_model.types module

class curobo.cuda_robot_model.types.JointType(value)

Bases: Enum

An enumeration.

FIXED = -1
X_PRISM = 0
Y_PRISM = 1
Z_PRISM = 2
X_ROT = 3
Y_ROT = 4
Z_ROT = 5
X_PRISM_NEG = 6
Y_PRISM_NEG = 7
Z_PRISM_NEG = 8
X_ROT_NEG = 9
Y_ROT_NEG = 10
Z_ROT_NEG = 11
class curobo.cuda_robot_model.types.JointLimits(joint_names: 'List[str]', position: 'torch.Tensor', velocity: 'torch.Tensor', acceleration: 'torch.Tensor', jerk: 'torch.Tensor', effort: 'Optional[torch.Tensor]' = None, tensor_args: 'TensorDeviceType' = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32))

Bases: object

Parameters:
  • joint_names (List[str]) –

  • position (Tensor) –

  • velocity (Tensor) –

  • acceleration (Tensor) –

  • jerk (Tensor) –

  • effort (Tensor | None) –

  • tensor_args (TensorDeviceType) –

joint_names: List[str]
position: Tensor
velocity: Tensor
acceleration: Tensor
jerk: Tensor
effort: Tensor | None = None
tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32)
static from_data_dict(data, tensor_args=TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32))
Parameters:
clone()
Return type:

JointLimits

copy_(new_jl)
Parameters:

new_jl (JointLimits) –

class curobo.cuda_robot_model.types.CSpaceConfig(joint_names: 'List[str]', retract_config: 'Optional[T_DOF]' = None, cspace_distance_weight: 'Optional[T_DOF]' = None, null_space_weight: 'Optional[T_DOF]' = None, tensor_args: 'TensorDeviceType' = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32), max_acceleration: 'Union[float, List[float]]' = 10.0, max_jerk: 'Union[float, List[float]]' = 500.0, velocity_scale: 'Union[float, List[float]]' = 1.0, acceleration_scale: 'Union[float, List[float]]' = 1.0, jerk_scale: 'Union[float, List[float]]' = 1.0, position_limit_clip: 'Union[float, List[float]]' = 0.0)

Bases: object

Parameters:
  • joint_names (List[str]) –

  • retract_config (Tensor | None) –

  • cspace_distance_weight (Tensor | None) –

  • null_space_weight (Tensor | None) –

  • tensor_args (TensorDeviceType) –

  • max_acceleration (float | List[float]) –

  • max_jerk (float | List[float]) –

  • velocity_scale (float | List[float]) –

  • acceleration_scale (float | List[float]) –

  • jerk_scale (float | List[float]) –

  • position_limit_clip (float | List[float]) –

joint_names: List[str]
retract_config: Tensor | None = None
cspace_distance_weight: Tensor | None = None
null_space_weight: Tensor | None = None
tensor_args: TensorDeviceType = TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32)
max_acceleration: float | List[float] = 10.0
max_jerk: float | List[float] = 500.0
velocity_scale: float | List[float] = 1.0
acceleration_scale: float | List[float] = 1.0
jerk_scale: float | List[float] = 1.0
position_limit_clip: float | List[float] = 0.0
inplace_reindex(joint_names)
Parameters:

joint_names (List[str]) –

copy_(new_config)
Parameters:

new_config (CSpaceConfig) –

clone()
Return type:

CSpaceConfig

scale_joint_limits(joint_limits)
Parameters:

joint_limits (JointLimits) –

static load_from_joint_limits(joint_position_upper, joint_position_lower, joint_names, tensor_args=TensorDeviceType(device=device(type='cuda', index=0), dtype=torch.float32))
Parameters:
  • joint_position_upper (Tensor) –

  • joint_position_lower (Tensor) –

  • joint_names (List[str]) –

  • tensor_args (TensorDeviceType) –

class curobo.cuda_robot_model.types.KinematicsTensorConfig(fixed_transforms: 'torch.Tensor', link_map: 'torch.Tensor', joint_map: 'torch.Tensor', joint_map_type: 'torch.Tensor', store_link_map: 'torch.Tensor', link_chain_map: 'torch.Tensor', link_names: 'List[str]', joint_limits: 'JointLimits', non_fixed_joint_names: 'List[str]', n_dof: 'int', mesh_link_names: 'Optional[List[str]]' = None, joint_names: 'Optional[List[str]]' = None, lock_jointstate: 'Optional[JointState]' = None, link_spheres: 'Optional[torch.Tensor]' = None, link_sphere_idx_map: 'Optional[torch.Tensor]' = None, link_name_to_idx_map: 'Optional[Dict[str, int]]' = None, total_spheres: 'int' = 0, debug: 'Optional[Any]' = None, ee_idx: 'int' = 0, cspace: 'Optional[CSpaceConfig]' = None, base_link: 'str' = 'base_link', ee_link: 'str' = 'ee_link', reference_link_spheres: 'Optional[torch.Tensor]' = None)

Bases: object

Parameters:
  • fixed_transforms (Tensor) –

  • link_map (Tensor) –

  • joint_map (Tensor) –

  • joint_map_type (Tensor) –

  • store_link_map (Tensor) –

  • link_chain_map (Tensor) –

  • link_names (List[str]) –

  • joint_limits (JointLimits) –

  • non_fixed_joint_names (List[str]) –

  • n_dof (int) –

  • mesh_link_names (List[str] | None) –

  • joint_names (List[str] | None) –

  • lock_jointstate (JointState | None) –

  • link_spheres (Tensor | None) –

  • link_sphere_idx_map (Tensor | None) –

  • link_name_to_idx_map (Dict[str, int] | None) –

  • total_spheres (int) –

  • debug (Any | None) –

  • ee_idx (int) –

  • cspace (CSpaceConfig | None) –

  • base_link (str) –

  • ee_link (str) –

  • reference_link_spheres (Tensor | None) –

fixed_transforms: Tensor
joint_map: Tensor
joint_map_type: Tensor
joint_limits: JointLimits
non_fixed_joint_names: List[str]
n_dof: int
joint_names: List[str] | None = None
lock_jointstate: JointState | None = None
total_spheres: int = 0
debug: Any | None = None
ee_idx: int = 0
cspace: CSpaceConfig | None = None
copy_(new_config)
Parameters:

new_config (KinematicsTensorConfig) –

load_cspace_cfg_from_kinematics()
Parameters:

link_name (str) –

Return type:

Tensor

Update sphere parameters

#NOTE: This currently does not update self collision distances. :param link_name: _description_ :param sphere_position_radius: _description_ :param start_sph_idx: _description_. Defaults to 0.

Parameters:
  • link_name (str) –

  • sphere_position_radius (Tensor) –

  • start_sph_idx (int) –

Parameters:

link_name (str) –

Parameters:

link_name (str) –

attach_object(sphere_radius=None, sphere_tensor=None, link_name='attached_object')

_summary_

Parameters:
  • sphere_radius (float | None) – _description_. Defaults to None.

  • sphere_tensor (Tensor | None) – _description_. Defaults to None.

  • link_name (str) – _description_. Defaults to “attached_object”.

Raises:
  • ValueError – _description_

  • ValueError – _description_

Returns:

_description_

Return type:

bool

detach_object(link_name='attached_object')

Detach object from robot end-effector

Parameters:

link_name (str) – _description_. Defaults to “attached_object”.

Raises:

ValueError – _description_

Returns:

_description_

Return type:

bool

get_number_of_spheres(link_name)

Get number of spheres for a link

Parameters:

link_name (str) – name of link

Return type:

int

Parameters:

link_name (str) –

Parameters:

link_name (str) –

class curobo.cuda_robot_model.types.SelfCollisionKinematicsConfig(offset=None, distance_threshold=None, thread_location=None, thread_max=None, collision_matrix=None, experimental_kernel=True, checks_per_thread=32)

Bases: object

Dataclass that stores self collision attributes to pass to cuda kernel.

Parameters:
  • offset (Tensor | None) –

  • distance_threshold (Tensor | None) –

  • thread_location (Tensor | None) –

  • thread_max (int | None) –

  • collision_matrix (Tensor | None) –

  • experimental_kernel (bool) –

  • checks_per_thread (int) –

offset: Tensor | None = None
distance_threshold: Tensor | None = None
thread_location: Tensor | None = None
thread_max: int | None = None
collision_matrix: Tensor | None = None
experimental_kernel: bool = True
checks_per_thread: int = 32
class curobo.cuda_robot_model.types.CudaRobotModelState(ee_position, ee_quaternion, lin_jacobian=None, ang_jacobian=None, links_position=None, links_quaternion=None, link_spheres_tensor=None, link_names=None)

Bases: object

Dataclass that stores kinematics information.

Parameters:
  • ee_position (Tensor) –

  • ee_quaternion (Tensor) –

  • lin_jacobian (Tensor | None) –

  • ang_jacobian (Tensor | None) –

  • links_position (Tensor | None) –

  • links_quaternion (Tensor | None) –

  • link_spheres_tensor (Tensor | None) –

  • link_names (str | None) –

ee_position: Tensor

End-effector position stored as x,y,z in meters [b, 3]. End-effector is defined by curobo.cuda_robot_model.cuda_robot_generator.CudaRobotGeneratorConfig.ee_link.

ee_quaternion: Tensor
lin_jacobian: Tensor | None = None

Linear Jacobian. Currently not supported.

ang_jacobian: Tensor | None = None

Angular Jacobian. Currently not supported.

Position of links specified by link_names (CudaRobotModelConfig.link_names).

Quaternions of links specified by link names (CudaRobotModelConfig.link_names).

Position of spheres specified by collision spheres (CudaRobotModelConfig.collision_spheres) in x, y, z, r format [b,n,4].

property ee_pose