curobo.cuda_robot_model.kinematics_parser module

class LinkParams(
link_name: str,
joint_name: str,
joint_type: curobo.cuda_robot_model.types.JointType,
fixed_transform: numpy.ndarray,
parent_link_name: Optional[str] = None,
joint_limits: Optional[List[float]] = None,
joint_axis: Optional[numpy.ndarray] = None,
joint_id: Optional[int] = None,
joint_velocity_limits: List[float] = <factory>,
joint_offset: List[float] = <factory>,
mimic_joint_name: Optional[str] = None,
)

Bases: object

joint_name: str
joint_type: JointType
fixed_transform: ndarray
joint_limits: List[float] | None = None
joint_axis: ndarray | None = None
joint_id: int | None = None
joint_velocity_limits: List[float]
joint_offset: List[float]
mimic_joint_name: str | None = None
static from_dict(dict_data)
class KinematicsParser(
extra_links: Dict[str, LinkParams] | None = None,
)

Bases: object

Build a map of parent links to each link in the kinematic tree.

NOTE: Use this function to fill self._parent_map.

get_chain(
base_link: str,
ee_link: str,
) List[str]

Get list of links attaching ee_link to base_link.

Parameters:
  • base_link (str) – Name of base link.

  • ee_link (str) – Name of end-effector link.

Returns:

List of link names starting from base_link to ee_link.

Return type:

List[str]