curobo.cuda_robot_model.types module¶
Common structures used for Kinematics are defined in this module.
- class JointType(value)¶
Bases:
Enum
Type of Joint. Arbitrary axis of change is not supported.
- FIXED = -1¶
Fixed joint.
- X_PRISM = 0¶
Prismatic joint along x-axis.
- Y_PRISM = 1¶
Prismatic joint along y-axis.
- Z_PRISM = 2¶
Prismatic joint along z-axis.
- X_ROT = 3¶
Revolute joint along x-axis.
- Y_ROT = 4¶
Revolute joint along y-axis.
- Z_ROT = 5¶
Revolute joint along z-axis.
- X_PRISM_NEG = 6¶
Prismatic joint along negative x-axis.
- Y_PRISM_NEG = 7¶
Prismatic joint along negative y-axis.
- Z_PRISM_NEG = 8¶
Prismatic joint along negative z-axis.
- X_ROT_NEG = 9¶
Revolute joint along negative x-axis.
- Y_ROT_NEG = 10¶
Revolute joint along negative y-axis.
- Z_ROT_NEG = 11¶
Revolute joint along negative z-axis.
- class JointLimits(
- 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, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_dtype=torch.float32),
Bases:
object
Joint limits for a robot.
- position: Tensor¶
Position limits for each joint. Shape [n_joints, 2] with columns having [min, max] values.
- velocity: Tensor¶
Velocity limits for each joint. Shape [n_joints, 2] with columns having [min, max] values.
- acceleration: Tensor¶
Acceleration limits for each joint. Shape [n_joints, 2] with columns having [min, max] values.
- jerk: Tensor¶
Jerk limits for each joint. Shape [n_joints, 2] with columns having [min, max] values.
- 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 and floating point precision for tensors.
- 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),
Create JointLimits from a dictionary.
- Parameters:
data – Dictionary containing joint limits. E.g., {“position”: [0, 1], …}.
tensor_args – Device and floating point precision for tensors.
- Returns:
Joint limits instance.
- Return type:
- clone() JointLimits ¶
Clone joint limits.
- copy_(
- new_jl: JointLimits,
Copy joint limits from another instance. This maintains reference and copies the data.
- Parameters:
new_jl – JointLimits instance to copy from.
- Returns:
Data copied joint limits.
- Return type:
- class CSpaceConfig(
- 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, collision_geometry_dtype=torch.float32, collision_gradient_dtype=torch.float32, collision_distance_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,
Bases:
object
Configuration space parameters of the robot.
- retract_config: Tensor | None = None¶
Retract configuration for the robot. This is the configuration used to bias graph search and also regularize inverse kinematics. This configuration is also used to initialize the robot during warmup phase of an optimizer. Set this to a collision-free configuration for good performance. When this configuration is in collision, it’s not used to bias graph search.
- cspace_distance_weight: Tensor | None = None¶
Weight for each joint in configuration space. Used to measure distance between nodes in graph search-based planning.
- null_space_weight: Tensor | None = None¶
Weight for each joint, used in regularization cost term for inverse kinematics.
- 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 and floating point precision for tensors.
- max_acceleration: float | List[float] = 10.0¶
Maximum acceleration for each joint. Accepts a scalar or a list of values for each joint.
- max_jerk: float | List[float] = 500.0¶
Maximum jerk for each joint. Accepts a scalar or a list of values for each joint.
- velocity_scale: float | List[float] = 1.0¶
Velocity scale for each joint. Accepts a scalar or a list of values for each joint. This is used to scale the velocity limits for each joint.
- acceleration_scale: float | List[float] = 1.0¶
Acceleration scale for each joint. Accepts a scalar or a list of values for each joint. This is used to scale the acceleration limits for each joint.
- jerk_scale: float | List[float] = 1.0¶
Jerk scale for each joint. Accepts a scalar or a list of values for each joint. This is used to scale the jerk limits for each joint.
- position_limit_clip: float | List[float] = 0.0¶
Position limit clip value. This is used to clip the position limits for each joint. Accepts a scalar or a list of values for each joint. This is useful to truncate limits to account for any safety margins imposed by real robot controllers.
- inplace_reindex( )¶
Change order of joints in configuration space tensors to match given order of names.
- Parameters:
joint_names – New order of joint names.
- copy_(
- new_config: CSpaceConfig,
Copy parameters from another instance.
This maintains reference and copies the data. Assumes that the new instance has the same number of joints as the current instance and also same shape of tensors.
- Parameters:
new_config – New parameters to copy into current instance.
- Returns:
Same instance of cspace configuration which has updated parameters.
- Return type:
- clone() CSpaceConfig ¶
Clone configuration space parameters.
- scale_joint_limits(
- joint_limits: JointLimits,
Scale joint limits by the given scale factors.
- Parameters:
joint_limits – Joint limits to scale.
- Returns:
Scaled joint limits.
- Return type:
- 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),
Load CSpace configuration from joint limits.
- Parameters:
joint_position_upper – Upper position limits for each joint.
joint_position_lower – Lower position limits for each joint.
joint_names – Names of the joints. This should match the order of joints in the upper and lower limits.
tensor_args – Device and floating point precision for tensors.
- Returns:
- CSpace configuration with retract configuration set to the middle of the
joint limits and all weights set to 1.
- Return type:
- 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¶
Name of joints to lock to a fixed value along with the locked value
- link_spheres: Tensor | None = None¶
Sphere representation of the robot’s geometry. This is used for collision detection.
- link_sphere_idx_map: Tensor | None = None¶
Mapping of link index to sphere index. This is used to get spheres for a link.
- link_name_to_idx_map: Dict[str, int] | None = None¶
Mapping of link name to link index. This is used to get link index from link name.
- cspace: CSpaceConfig | None = None¶
Cspace parameters for the robot.
- 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,
Copy parameters from another instance into current instance.
This maintains reference and copies the data. Assumes that the new instance has the same number of joints as the current instance and also same shape of tensors.
- Parameters:
new_config – New parameters to copy into current instance.
- Returns:
- Same instance of kinematics configuration which has updated
parameters.
- Return type:
- load_cspace_cfg_from_kinematics()¶
Load CSpace configuration from joint limits.
This sets the retract configuration to the middle of the joint limits and all weights to 1.
- get_sphere_index_from_link_name(
- link_name: str,
Get indices of spheres for a link.
- Parameters:
link_name – Name of the link.
- Returns:
Indices of spheres for the link.
- Return type:
- update_link_spheres( )¶
Update sphere parameters of a specific link given by name.
- Parameters:
link_name – Name of the link.
sphere_position_radius – Tensor of shape [n_spheres, 4] with columns [x, y, z, r].
start_sph_idx – If providing a subset of spheres, this is the starting index.
- get_link_spheres(
- link_name: str,
Get spheres of a link.
- Parameters:
link_name – Name of link.
- Returns:
Spheres of the link with shape [n_spheres, 4] with columns [x, y, z, r].
- Return type:
- get_reference_link_spheres(
- link_name: str,
Get link spheres from the original robot configuration data before any modifications.
- Parameters:
link_name – Name of link.
- Returns:
Spheres of the link with shape [n_spheres, 4] with columns [x, y, z, r].
- Return type:
- attach_object(
- sphere_radius: float | None = None,
- sphere_tensor: Tensor | None = None,
- link_name: str = 'attached_object',
Attach object approximated by spheres to a link of the robot.
This function updates the sphere parameters of the link to represent the attached object.
- Parameters:
sphere_radius – Radius to change for existing spheres. If changing position of spheres as well, then set this to None.
sphere_tensor – New sphere tensor to replace existing spheres. Shape [n_spheres, 4] with columns [x, y, z, r]. If changing only radius, set this to None and use sphere_radius.
link_name – Name of the link to attach object to. Defaults to “attached_object”.
- Returns:
True if successful.
- Return type:
- detach_object(
- link_name: str = 'attached_object',
Detach object spheres from a link by setting all spheres to zero with negative radius.
- Parameters:
link_name – Name of the link to detach object from.
- Returns:
True if successful.
- Return type:
- get_number_of_spheres(
- link_name: str,
Get number of spheres for a link
- Parameters:
link_name – name of link
- class SelfCollisionKinematicsConfig(
- offset: Tensor | None = None,
- thread_location: Tensor | None = None,
- thread_max: int | None = None,
- distance_threshold: Tensor | None = None,
- experimental_kernel: bool = True,
- collision_matrix: Tensor | None = None,
- checks_per_thread: int = 32,
Bases:
object
Dataclass that stores self collision attributes to pass to cuda kernel.
- offset: Tensor | None = None¶
Offset radii for each sphere. This is used to inflate the spheres for self collision detection.
- thread_max: int | None = None¶
Maximum number of threads to launch for computing self collision between spheres.
- distance_threshold: Tensor | None = None¶
Distance threshold for self collision detection. This is currently not used.
- experimental_kernel: bool = True¶
Two kernel implementations are available. Set this to True to use the experimental kernel which is faster. Set this to False to use the collision matrix based kernel which is slower.