curobo.cuda_robot_model.types module
- class 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 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, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Bases:
object
- 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,
- 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),
- clone() JointLimits
- copy_(
- new_jl: JointLimits,
- class 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, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_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
- 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)
- copy_(
- new_config: CSpaceConfig,
- clone() CSpaceConfig
- scale_joint_limits(
- joint_limits: JointLimits,
- static load_from_joint_limits(
- joint_position_upper: Tensor,
- joint_position_lower: Tensor,
- joint_names: List[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),
- class KinematicsTensorConfig(
- fixed_transforms: Tensor,
- link_map: Tensor,
- joint_map: Tensor,
- joint_map_type: Tensor,
- joint_offset_map: 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 = None,
- joint_names: List[str] | None = None,
- lock_jointstate: JointState | None = None,
- mimic_joints: dict | None = None,
- link_spheres: Tensor | None = None,
- link_sphere_idx_map: Tensor | None = None,
- link_name_to_idx_map: Dict[str, int] | None = None,
- total_spheres: int = 0,
- debug: Any | None = None,
- ee_idx: int = 0,
- cspace: CSpaceConfig | None = None,
- base_link: str = 'base_link',
- ee_link: str = 'ee_link',
- reference_link_spheres: Tensor | None = None,
Bases:
object
Stores robot’s kinematics parameters as Tensors to use in Kinematics computations.
Use
curobo.cuda_robot_model.cuda_robot_generator.CudaRobotGenerator
to generate this configuration from a urdf or usd.- fixed_transforms: Tensor
Static Homogenous Transform from parent link to child link for all links [n_links,4,4].
- link_chain_map: Tensor
Mapping between each link to every other link, this is used to check if a link is part of a serial chain formed by another link [n_links, n_links].
- joint_limits: JointLimits
Joint limits
- mesh_link_names: List[str] | None = None
Name of links which have a mesh. Currently only used for debugging and rendering.
- lock_jointstate: JointState | None = None
- cspace: CSpaceConfig | None = None
Cspace configuration
- base_link: str = 'base_link'
Name of base link. This is the root link from which all kinematic parameters were computed.
- reference_link_spheres: Tensor | None = None
A copy of link spheres that is used as reference, in case the link_spheres get modified at runtime.
- copy_(
- new_config: KinematicsTensorConfig,
- load_cspace_cfg_from_kinematics()
- update_link_spheres( )
Update sphere parameters
NOTE: This currently does not update self collision distances.
- Parameters:
link_name – _description_
sphere_position_radius – _description_
start_sph_idx – _description_. Defaults to 0.
- attach_object(
- sphere_radius: float | None = None,
- sphere_tensor: Tensor | None = None,
- link_name: str = 'attached_object',
_summary_
- Parameters:
sphere_radius – _description_. Defaults to None.
sphere_tensor – _description_. Defaults to None.
link_name – _description_. Defaults to “attached_object”.
- Raises:
ValueError – _description_
ValueError – _description_
- Returns:
_description_
- detach_object(
- link_name: str = 'attached_object',
Detach object from robot end-effector
- Parameters:
link_name – _description_. Defaults to “attached_object”.
- Raises:
ValueError – _description_
- Returns:
_description_
- class SelfCollisionKinematicsConfig(
- 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,
Bases:
object
Dataclass that stores self collision attributes to pass to cuda kernel.