curobo.cuda_robot_model.cuda_robot_model module¶
This module builds a kinematic representation of a robot on the GPU and provides differentiable mapping from it’s joint configuration to Cartesian pose of it’s links (forward kinematics). This module also computes the position of the spheres of the robot as part of the forward kinematics function.
- class CudaRobotModelConfig(
- tensor_args: TensorDeviceType,
- link_names: List[str],
- kinematics_config: KinematicsTensorConfig,
- self_collision_config: SelfCollisionKinematicsConfig | None = None,
- kinematics_parser: KinematicsParser | None = None,
- compute_jacobian: bool = False,
- use_global_cumul: bool = True,
- generator_config: CudaRobotGeneratorConfig | None = None,
Bases:
object
Configuration for robot kinematics on GPU.
Helper functions are provided to load this configuration from an URDF file or from a cuRobo robot configuration file (Configuring a New Robot). To create from a XRDF, use curobo.util.xrdf_utils.convert_xrdf_to_curobo.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for kinematics.
- kinematics_config: KinematicsTensorConfig¶
Tensors representing kinematics of the robot. This can be created using
CudaRobotGenerator
.
- self_collision_config: SelfCollisionKinematicsConfig | None = None¶
Collision pairs to ignore when computing self collision between spheres across all robot links. This also contains distance threshold between spheres pairs and which thread indices for calculating the distances. More details on computing these parameters is in
_build_collision_model
.
- kinematics_parser: KinematicsParser | None = None¶
Parser to load kinematics from URDF or USD files. This is used to load kinematics representation of the robot. This is created using
KinematicsParser
. USD is an experimental feature and might not work for all robots.
- compute_jacobian: bool = False¶
Output jacobian during forward kinematics. This is not implemented. The forward kinematics function does use Jacobian during backward pass. What’s not supported is
- use_global_cumul: bool = True¶
Store transformation matrix of every link during forward kinematics call in global memory. This helps speed up backward pass as we don’t need to recompute the transformation matrices. However, this increases memory usage and also slightly slows down forward kinematics. Enabling this is recommended for getting the best performance.
- generator_config: CudaRobotGeneratorConfig | None = None¶
Generator config used to create this robot kinematics model.
- get_joint_limits() JointLimits ¶
Get limits of actuated joints of the robot.
- Returns:
Joint limits of the robot’s actuated joints.
- Return type:
- 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_content_path(
- content_path: ContentPath,
- 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),
Load robot from Contentpath containing paths to robot description files.
- Parameters:
content_path – Path to robot configuration files.
ee_link – End-effector link name. If None, it is read from the file.
tensor_args – Device to load robot model, defaults to cuda:0.
- Returns:
cuda robot model configuration.
- Return type:
- static from_robot_yaml_file(
- file_path: str | Dict,
- 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),
- urdf_path: str | None = None,
Load robot from a yaml file that is in cuRobo’s format (Configuring a New Robot).
- Parameters:
file_path – Path to robot configuration file (yml or xrdf).
ee_link – End-effector link name. If None, it is read from the file.
tensor_args – Device to load robot model, defaults to cuda:0.
urdf_path – Path to urdf file. This is required when loading a xrdf file.
- Returns:
cuda robot model configuration.
- Return type:
- 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),
Load robot from a dictionary containing data for
CudaRobotGeneratorConfig
.:tut_robot_configuration discusses the data required to load a robot.
- Parameters:
data_dict – Input dictionary containing robot configuration.
tensor_args – Device to load robot model, defaults to cuda:0.
- Returns:
cuda robot model configuration.
- Return type:
- static from_config(
- config: CudaRobotGeneratorConfig,
Create a robot model configuration from a generator configuration.
- Parameters:
config – Input robot generator configuration.
- Returns:
robot model configuration.
- Return type:
- property cspace: CSpaceConfig¶
Get cspace parameters of the robot.
- 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
Kinematic state of robot.
- 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
Load basic kinematics from an URDF with
from_basic_urdf
. Check Configuring a New Robot for details on how to also create a geometric representation of the robot. 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.Initialize kinematics instance with a robot model configuration.
- Parameters:
config – Input robot model configuration.
- update_batch_size( )¶
Update batch size of the robot model.
- Parameters:
batch_size – Batch size to update the robot model.
force_update – Detach gradients of tensors. This is not supported.
reset_buffers – Recreate the tensors even if the batch size is same.
- forward(
- q,
- link_name=None,
- calculate_jacobian=False,
Compute forward kinematics of the robot.
Use
get_state
to get a structured output.- Parameters:
q – Joint configuration of the robot. Shape should be [batch_size, dof].
link_name – Name of link to return pose of. If None, returns end-effector pose.
calculate_jacobian – Calculate jacobian of the robot. Not supported.
- Returns:
End-effector position, end-effector quaternion (wxyz), linear jacobian(None), angular jacobian(None), link positions, link quaternion (wxyz), link spheres.
- Return type:
Tuple[Tensor, Tensor, None, None, Tensor, Tensor, Tensor]
- get_state( ) CudaRobotModelState ¶
Get kinematic state of the robot by computing forward kinematics.
- Parameters:
q – Joint configuration of the robot. Shape should be [batch_size, dof].
link_name – Name of link to return pose of. If None, returns end-effector pose.
calculate_jacobian – Calculate jacobian of the robot. Not supported.
- Returns:
Kinematic state of the robot.
- Return type:
- compute_kinematics(
- js: JointState,
- link_name: str | None = None,
- calculate_jacobian: bool = False,
Compute forward kinematics of the robot.
- Parameters:
js – Joint state of robot.
link_name – Name of link to return pose of. If None, returns end-effector pose.
calculate_jacobian – Calculate jacobian of the robot. Not supported.
- Returns:
Kinematic state of the robot.
- Return type:
- compute_kinematics_from_joint_state(
- js: JointState,
- link_name: str | None = None,
- calculate_jacobian: bool = False,
Compute forward kinematics of the robot.
- Parameters:
js – Joint state of robot.
link_name – Name of link to return pose of. If None, returns end-effector pose.
calculate_jacobian – Calculate jacobian of the robot. Not supported.
- Returns:
Kinematic state of the robot.
- Return type:
- compute_kinematics_from_joint_position( ) CudaRobotModelState ¶
Compute forward kinematics of the robot.
- Parameters:
joint_position – Joint position of robot. Assumed to only contain active joints in the order specified in
CudaRobotModel.joint_names
.link_name – Name of link to return pose of. If None, returns end-effector pose.
calculate_jacobian – Calculate jacobian of the robot. Not supported.
- Returns:
Kinematic state of the robot.
- Return type:
- get_robot_link_meshes() List[Mesh] ¶
Get meshes of all links of the robot.
- Returns:
List of all link meshes.
- Return type:
List[Mesh]
- get_robot_as_mesh(
- q: Tensor,
Transform robot links to Cartesian poses using forward kinematics and return as meshes.
- Parameters:
q – Joint configuration of the robot, shape should be [1, dof].
- Returns:
List of all link meshes.
- Return type:
List[Mesh]
- get_robot_as_spheres( ) List[Sphere] ¶
Get robot spheres using forward kinematics on given joint configuration q.
- Parameters:
q – Joint configuration of the robot, shape should be [1, dof].
filter_valid – Filter out spheres with radius <= 0.
- Returns:
List of all robot spheres.
- Return type:
List[Sphere]
- get_link_poses( ) Pose ¶
Get Pose of links at given joint configuration q using forward kinematics.
Note that only the links specified in
link_names
are returned.- Parameters:
q – Joint configuration of the robot, shape should be [batch_size, dof].
link_names – Names of links to get pose of. This should be a subset of
link_names
.
- Returns:
Poses of links at given joint configuration.
- Return type:
- _cuda_forward(
- q: torch.Tensor,
Compute forward kinematics on GPU. Use
get_state
orforward
instead.- Parameters:
q – Joint configuration of the robot, shape should be [batch_size, dof].
- Returns:
Link positions, link quaternions, link
- Return type:
Tuple[Tensor, Tensor, Tensor]
- get_self_collision_config() SelfCollisionKinematicsConfig ¶
Get self collision configuration parameters of the robot.
- get_link_transform(
- link_name: str,
Get pose offset of a link from it’s parent joint.
- Parameters:
link_name – Name of link to get pose of.
- Returns:
Pose of the link.
- Return type:
- property lock_jointstate: JointState¶
State of joints that are locked in the kinematic representation.
- get_full_js(
- js: JointState,
Get state of all joints, including locked joints.
This function will not provide state of mimic joints. If you need mimic joints, use
get_mimic_js
.- Parameters:
js – State containing articulated joints.
- Returns:
State of all joints.
- Return type:
- get_mimic_js(
- js: JointState,
Get state of mimic joints from active joints.
Current implementation uses a for loop over joints to calculate the state. This can be optimized by using a custom CUDA kernel or a matrix multiplication.
- Parameters:
js – State containing articulated joints.
- Returns:
State of active, locked, and mimic joints.
- Return type:
- update_kinematics_config(
- new_kin_config: KinematicsTensorConfig,
Update kinematics representation of the robot.
A kinematics representation can be updated with new parameters. Some parameters that could require updating are state of locked joints, when a robot grasps an object. Another instance is when using different planners for different parts of the robot, example updating the state of robot base or another arm. Updations should result in the same tensor dimensions, if not then the instance of this class requires reinitialization.
- Parameters:
new_kin_config – New kinematics representation of the robot.
- attach_external_objects_to_robot(
- joint_state: JointState,
- external_objects: List[Obstacle],
- surface_sphere_radius: float = 0.001,
- link_name: str = 'attached_object',
- sphere_fit_type: SphereFitType = SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE,
- voxelize_method: str = 'ray',
- world_objects_pose_offset: Pose | None = None,
Attach external objects to a robot’s link. See Geometry Approximation to Spheres for details.
- Parameters:
joint_state – Joint state of the robot.
external_objects – List of external objects to attach to the robot.
surface_sphere_radius – Radius (in meters) to use for points sampled on surface of the object. A smaller radius will allow for generating motions very close to obstacles.
link_name – Name of the link (frame) to attach the objects to. The assumption is that this link does not have any geometry and all spheres of this link represent attached objects.
sphere_fit_type – Sphere fit algorithm to use. See Geometry Approximation to Spheres for more details. The default method
SphereFitType.VOXEL_VOLUME_SAMPLE_SURFACE
voxelizes the volume of the objects and adds spheres representing the voxels, then samples points on the surface of the object, addssurface_sphere_radius
to these points. This should be used for most cases.voxelize_method – Method to use for voxelization, passed to
trimesh.voxel.creation.voxelize
.world_objects_pose_offset – Offset to apply to the object poses before attaching to the robot. This is useful when attaching an object that’s in contact with the world. The offset is applied in the world frame before attaching to the robot.
- get_active_js(
- full_js: JointState,
Get joint state of active joints of the robot.
- Parameters:
full_js – Joint state of all joints.
- Returns:
Joint state of active joints.
- Return type:
- property robot_spheres¶
Spheres representing robot geometry.
- property retract_config: Tensor¶
Retract configuration of the robot. Use
joint_names
to get joint names.
- compute_jacobian: bool = False¶
Output jacobian during forward kinematics. This is not implemented. The forward kinematics function does use Jacobian during backward pass. What’s not supported is
- property cspace: CSpaceConfig¶
Get cspace parameters of the robot.
- 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,
Create a robot model configuration from a generator configuration.
- Parameters:
config – Input robot generator configuration.
- Returns:
robot model configuration.
- Return type:
- static from_content_path(
- content_path: ContentPath,
- 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),
Load robot from Contentpath containing paths to robot description files.
- Parameters:
content_path – Path to robot configuration files.
ee_link – End-effector link name. If None, it is read from the file.
tensor_args – Device to load robot model, defaults to cuda:0.
- Returns:
cuda robot model configuration.
- Return type:
- 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),
Load robot from a dictionary containing data for
CudaRobotGeneratorConfig
.:tut_robot_configuration discusses the data required to load a robot.
- Parameters:
data_dict – Input dictionary containing robot configuration.
tensor_args – Device to load robot model, defaults to cuda:0.
- Returns:
cuda robot model configuration.
- Return type:
- static from_robot_yaml_file(
- file_path: str | Dict,
- 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),
- urdf_path: str | None = None,
Load robot from a yaml file that is in cuRobo’s format (Configuring a New Robot).
- Parameters:
file_path – Path to robot configuration file (yml or xrdf).
ee_link – End-effector link name. If None, it is read from the file.
tensor_args – Device to load robot model, defaults to cuda:0.
urdf_path – Path to urdf file. This is required when loading a xrdf file.
- Returns:
cuda robot model configuration.
- Return type:
- generator_config: CudaRobotGeneratorConfig | None = None¶
Generator config used to create this robot kinematics model.
- get_joint_limits() JointLimits ¶
Get limits of actuated joints of the robot.
- Returns:
Joint limits of the robot’s actuated joints.
- Return type:
- kinematics_parser: KinematicsParser | None = None¶
Parser to load kinematics from URDF or USD files. This is used to load kinematics representation of the robot. This is created using
KinematicsParser
. USD is an experimental feature and might not work for all robots.
- self_collision_config: SelfCollisionKinematicsConfig | None = None¶
Collision pairs to ignore when computing self collision between spheres across all robot links. This also contains distance threshold between spheres pairs and which thread indices for calculating the distances. More details on computing these parameters is in
_build_collision_model
.
- use_global_cumul: bool = True¶
Store transformation matrix of every link during forward kinematics call in global memory. This helps speed up backward pass as we don’t need to recompute the transformation matrices. However, this increases memory usage and also slightly slows down forward kinematics. Enabling this is recommended for getting the best performance.
- tensor_args: TensorDeviceType¶
Device and floating point precision to use for kinematics.
- kinematics_config: KinematicsTensorConfig¶
Tensors representing kinematics of the robot. This can be created using
CudaRobotGenerator
.