fastdev.robo¶
Submodules¶
Package Contents¶
- class fastdev.robo.Articulation(specs: ArticulationSpec | Sequence[ArticulationSpec], device: Device = 'cpu')[source]¶
Class to manage multiple articulations.
- Parameters:
specs (Sequence[ArticulationSpec]) – Articulation specifications.
device (str, optional) – Device to store tensors. Defaults to “cpu”.
Examples
>>> arti = Articulation(ArticulationSpec(urdf_or_mjcf_path="assets/robot_description/panda.urdf")) >>> link_poses = arti.forward_kinematics(torch.zeros(1, arti.total_num_dofs), clamp_joint_values=False) >>> torch.allclose(link_poses[0, -1, :3, 3], torch.tensor([0.0880, 0.0000, 0.8676]), atol=1e-3) True
- specs: Sequence[ArticulationSpec]¶
- num_arti: int¶
- total_num_dofs: int¶
- total_num_links: int¶
- total_num_full_joints: int¶
- device = 'cpu'¶
- static from_urdf_or_mjcf_paths(urdf_or_mjcf_paths: str | pathlib.Path | Sequence[str | pathlib.Path], mesh_dirs: str | pathlib.Path | Sequence[str | pathlib.Path] | None = None, device: Device = 'cpu') Articulation [source]¶
- Parameters:
urdf_or_mjcf_paths (Union[Union[str, pathlib.Path], Sequence[Union[str, pathlib.Path]]])
mesh_dirs (Optional[Union[Union[str, pathlib.Path], Sequence[Union[str, pathlib.Path]]]])
device (Device)
- Return type:
- static from_urdf_or_mjcf_path(urdf_or_mjcf_path: str | pathlib.Path | Sequence[str | pathlib.Path], mesh_dir: str | pathlib.Path | Sequence[str | pathlib.Path] | None = None, device: Device = 'cpu') Articulation [source]¶
Keep this method for compatibility with old code.
- Parameters:
urdf_or_mjcf_path (Union[Union[str, pathlib.Path], Sequence[Union[str, pathlib.Path]]])
mesh_dir (Optional[Union[Union[str, pathlib.Path], Sequence[Union[str, pathlib.Path]]]])
device (Device)
- Return type:
- property first_spec: ArticulationSpec¶
- Return type:
- property has_none_joint_limits: bool¶
- Return type:
bool
- property has_none_mimic_joint_limits: bool¶
- Return type:
bool
- property has_mimic_joints: bool¶
- Return type:
bool
- property joint_limits: Optional[jaxtyping.Float[torch.Tensor, total_num_dofs 2]]¶
- Return type:
Optional[jaxtyping.Float[torch.Tensor, total_num_dofs 2]]
- property num_dofs: int¶
- Return type:
int
- property active_joint_names: List[str] | List[List[str]]¶
- Return type:
Union[List[str], List[List[str]]]
- property mimic_joint_names: List[str] | List[List[str]]¶
- Return type:
Union[List[str], List[List[str]]]
- property link_names: List[str] | List[List[str]]¶
- Return type:
Union[List[str], List[List[str]]]
- get_packed_joint_limits(return_tensors: Literal['np', 'pt'] = 'np', return_mimic_joints: bool = False) numpy.ndarray | torch.Tensor | None [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
return_mimic_joints (bool)
- Return type:
Optional[Union[numpy.ndarray, torch.Tensor]]
- get_packed_link_indices_topological_order(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_packed_parent_link_indices(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_packed_link_joint_indices(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_packed_link_joint_types(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_packed_link_joint_origins(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_packed_link_joint_axes(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_packed_full_joint_axes(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_joint_first_indices(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_link_first_indices(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_packed_ancestor_links_mask(target_link_indices: jaxtyping.Int[torch.Tensor, num_arti], return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
target_link_indices (jaxtyping.Int[torch.Tensor, num_arti])
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_packed_zero_joint_values(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_zero_joint_values(return_tensors: Literal['np', 'pt'] = 'np') numpy.ndarray | torch.Tensor [source]¶
- Parameters:
return_tensors (Literal['np', 'pt'])
- Return type:
Union[numpy.ndarray, torch.Tensor]
- get_link_trimesh_meshes(mode: Literal['visual', 'collision'] = 'collision', return_empty_meshes: bool = False) Dict[str, trimesh.Trimesh] | List[Dict[str, trimesh.Trimesh]] [source]¶
- Parameters:
mode (Literal['visual', 'collision'])
return_empty_meshes (bool)
- Return type:
Union[Dict[str, trimesh.Trimesh], List[Dict[str, trimesh.Trimesh]]]
- apply_mimic_joints(joint_values: jaxtyping.Float[torch.Tensor, ... total_num_dofs], clamp_joint_values: bool = True) jaxtyping.Float[torch.Tensor, ... total_num_full_joints] [source]¶
- Parameters:
joint_values (jaxtyping.Float[torch.Tensor, ... total_num_dofs])
clamp_joint_values (bool)
- Return type:
jaxtyping.Float[torch.Tensor, … total_num_full_joints]
- forward_kinematics(joint_values: Union[jaxtyping.Float[torch.Tensor, ... total_num_dofs]], joint_names: Optional[Union[List[List[str]], List[str]]] = None, root_poses: Optional[Union[jaxtyping.Float[torch.Tensor, ... num_arti 4 4], jaxtyping.Float[torch.Tensor, ... 4 4]]] = None, clamp_joint_values: bool = True, use_warp: bool = True) jaxtyping.Float[torch.Tensor, ... total_num_links 4 4] [source]¶
Forward kinematics.
- Parameters:
joint_values (torch.Tensor) – Packed joint values of shape (…, total_num_dofs).
joint_names (List[List[str]], optional) – Joint names for each articulation. Defaults to None. Could be a single list of joint names if there is only one articulation.
root_poses (torch.Tensor, optional) – Root poses of shape (…, num_arti, 4, 4). Defaults to None. The num_arti dimension can be omitted only if a single articulation is being used.
clamp_joint_values (bool, optional) – Whether to clamp joint values to joint limits. Defaults to True.
use_warp (bool)
- Return type:
jaxtyping.Float[torch.Tensor, … total_num_links 4 4]
- jacobian(joint_values: jaxtyping.Float[torch.Tensor, ... total_num_dofs], joint_names: Optional[Union[List[List[str]], List[str]]] = None, root_poses: Optional[Union[jaxtyping.Float[torch.Tensor, ... num_arti 4 4], jaxtyping.Float[torch.Tensor, ... 4 4]]] = None, target_links: Optional[Union[str, List[str], int, List[int], jaxtyping.Int[torch.Tensor, num_arti]]] = None, clamp_joint_values: bool = True, use_warp: bool = True, return_target_link_poses: bool = False) Union[jaxtyping.Float[torch.Tensor, ... 6 total_num_dofs], Tuple[jaxtyping.Float[torch.Tensor, ... 6 total_num_dofs], jaxtyping.Float[torch.Tensor, ... num_arti 4 4]]] [source]¶
- Parameters:
joint_values (jaxtyping.Float[torch.Tensor, ... total_num_dofs])
joint_names (Optional[Union[List[List[str]], List[str]]])
root_poses (Optional[Union[jaxtyping.Float[torch.Tensor, ... num_arti 4 4], jaxtyping.Float[torch.Tensor, ... 4 4]]])
target_links (Optional[Union[str, List[str], int, List[int], jaxtyping.Int[torch.Tensor, num_arti]]])
clamp_joint_values (bool)
use_warp (bool)
return_target_link_poses (bool)
- Return type:
Union[jaxtyping.Float[torch.Tensor, … 6 total_num_dofs], Tuple[jaxtyping.Float[torch.Tensor, … 6 total_num_dofs], jaxtyping.Float[torch.Tensor, … num_arti 4 4]]]
- inverse_kinematics(target_link_poses: Union[jaxtyping.Float[torch.Tensor, ... num_arti 4 4], jaxtyping.Float[torch.Tensor, ... 4 4]], target_links: Optional[Union[str, List[str], int, List[int], torch.Tensor]] = None, use_warp: bool = False, max_iterations: int = 30, learning_rate: float = 0.2, tolerance: float = 0.001, damping: float = 0.0001, num_retries: int = 50, init_joint_values: Optional[jaxtyping.Float[torch.Tensor, ... total_num_dofs]] = None, jitter_strength: float = 1.0, return_success: bool = False) Union[jaxtyping.Float[torch.Tensor, ... total_num_dofs], Tuple[jaxtyping.Float[torch.Tensor, ... total_num_dofs], jaxtyping.Bool[torch.Tensor, ... num_arti]]] [source]¶
- Parameters:
target_link_poses (Union[jaxtyping.Float[torch.Tensor, ... num_arti 4 4], jaxtyping.Float[torch.Tensor, ... 4 4]])
target_links (Optional[Union[str, List[str], int, List[int], torch.Tensor]])
use_warp (bool)
max_iterations (int)
learning_rate (float)
tolerance (float)
damping (float)
num_retries (int)
init_joint_values (Optional[jaxtyping.Float[torch.Tensor, ... total_num_dofs]])
jitter_strength (float)
return_success (bool)
- Return type:
Union[jaxtyping.Float[torch.Tensor, … total_num_dofs], Tuple[jaxtyping.Float[torch.Tensor, … total_num_dofs], jaxtyping.Bool[torch.Tensor, … num_arti]]]
- apply_mimic_joints_numpy(joint_values: jaxtyping.Float[numpy.ndarray, ... total_num_dofs], clamp_joint_values: bool = True) jaxtyping.Float[numpy.ndarray, ... total_num_joints] [source]¶
- Parameters:
joint_values (jaxtyping.Float[numpy.ndarray, ... total_num_dofs])
clamp_joint_values (bool)
- Return type:
jaxtyping.Float[numpy.ndarray, … total_num_joints]
- forward_kinematics_numpy(joint_values: Union[jaxtyping.Float[numpy.ndarray, ... total_num_dofs]], joint_names: Optional[Union[List[List[str]], List[str]]] = None, root_poses: Optional[Union[jaxtyping.Float[numpy.ndarray, ... num_arti 4 4], jaxtyping.Float[numpy.ndarray, ... 4 4]]] = None, clamp_joint_values: bool = True) jaxtyping.Float[numpy.ndarray, ... total_num_links 4 4] [source]¶
Forward kinematics.
- Parameters:
joint_values (torch.Tensor) – Packed joint values of shape (…, total_num_dofs).
joint_names (List[List[str]], optional) – Joint names for each articulation. Defaults to None. Could be a single list of joint names if there is only one articulation.
root_poses (torch.Tensor, optional) – Root poses of shape (…, num_arti, 4, 4). Defaults to None. The num_arti dimension can be omitted only if a single articulation is being used.
clamp_joint_values (bool, optional) – Whether to clamp joint values to joint limits. Defaults to True.
- Return type:
jaxtyping.Float[numpy.ndarray, … total_num_links 4 4]
- to(device: Device) Articulation [source]¶
- Parameters:
device (Device)
- Return type:
- __getitem__(idx: int | slice) Articulation [source]¶
- Parameters:
idx (Union[int, slice])
- Return type:
- class fastdev.robo.ArticulationSpec(urdf_or_mjcf_path: str | pathlib.Path, mesh_dir: str | pathlib.Path | None = None, format: Literal['urdf', 'mjcf'] | None = None, base_link_name: str | None = None, ee_link_names: str | List[str] | None = None, mjcf_assets: Dict[str, Any] | None = None, enable_mimic_joints: bool = True)[source]¶
Specification for a single articulation.
- Parameters:
urdf_or_mjcf_path (str) – Path to the URDF or MJCF file.
mesh_dir (str, optional) – Directory to store mesh files. Defaults to None.
format (str, optional) – Format of the file, either “urdf” or “mjcf”. Defaults to None.
mjcf_assets (Dict[str, Any], optional) – Assets for MJCF files. Defaults to None.
enable_mimic_joints (bool, optional) – Whether to enable mimic joints. Defaults to True.
base_link_name (Optional[str])
ee_link_names (Optional[Union[str, List[str]]])
Examples
>>> arti_spec = ArticulationSpec(urdf_or_mjcf_path="assets/robot_description/panda.urdf") >>> arti_spec.num_dofs 8
- base_link_name: str¶
- ee_link_names: List[str]¶
- link_names: List[str]¶
- num_links: int¶
- num_dofs: int¶
- active_joint_names: List[str]¶
- has_mimic_joints: bool¶
- mimic_joint_names: List[str]¶
- full_joint_names: List[str]¶
- num_full_joints: int¶
- urdf_or_mjcf_path = ''¶
- mesh_dir = ''¶
- format = None¶
- mjcf_assets = None¶
- enable_mimic_joints = True¶
- num_mimic_joints¶
- parse_urdf() Tuple[Dict[str, Joint], Dict[str, Link]] [source]¶
- Return type:
Tuple[Dict[str, Joint], Dict[str, Link]]
- parse_mjcf() Tuple[Dict[str, Joint], Dict[str, Link]] [source]¶
- Return type:
Tuple[Dict[str, Joint], Dict[str, Link]]
- property joint_limits: Optional[jaxtyping.Float[numpy.ndarray, num_dofs 2]]¶
- Return type:
Optional[jaxtyping.Float[numpy.ndarray, num_dofs 2]]
- property mimic_joint_limits: Optional[jaxtyping.Float[numpy.ndarray, num_mimic_joints 2]]¶
- Return type:
Optional[jaxtyping.Float[numpy.ndarray, num_mimic_joints 2]]
- property mimic_joint_indices: jaxtyping.Int[numpy.ndarray, num_mimic_joints]¶
- Return type:
jaxtyping.Int[numpy.ndarray, num_mimic_joints]
- property mimic_multipliers: jaxtyping.Float[numpy.ndarray, num_mimic_joints]¶
- Return type:
jaxtyping.Float[numpy.ndarray, num_mimic_joints]
- property mimic_offsets: jaxtyping.Float[numpy.ndarray, num_mimic_joints]¶
- Return type:
jaxtyping.Float[numpy.ndarray, num_mimic_joints]
- property link_joint_indices: jaxtyping.Int[numpy.ndarray, num_links]¶
- Return type:
jaxtyping.Int[numpy.ndarray, num_links]
- property link_indices_topological_order: jaxtyping.Int[numpy.ndarray, num_links]¶
- Return type:
jaxtyping.Int[numpy.ndarray, num_links]
- property parent_link_indices: jaxtyping.Int[numpy.ndarray, num_links]¶
- Return type:
jaxtyping.Int[numpy.ndarray, num_links]
- property link_joint_axes: Optional[jaxtyping.Float[numpy.ndarray, num_links 3]]¶
- Return type:
Optional[jaxtyping.Float[numpy.ndarray, num_links 3]]
- property full_joint_axes: jaxtyping.Float[numpy.ndarray, num_full_joints 3]¶
- Return type:
jaxtyping.Float[numpy.ndarray, num_full_joints 3]
- property link_joint_origins: jaxtyping.Float[numpy.ndarray, num_links 4 4]¶
- Return type:
jaxtyping.Float[numpy.ndarray, num_links 4 4]
- property link_joint_types: jaxtyping.Int[numpy.ndarray, num_links]¶
- Return type:
jaxtyping.Int[numpy.ndarray, num_links]
- class fastdev.robo.RobotModel(specs: ArticulationSpec | Sequence[ArticulationSpec], device: Device = 'cpu')[source]¶
Bases:
Articulation
Class to manage multiple articulations.
- Parameters:
specs (Sequence[ArticulationSpec]) – Articulation specifications.
device (str, optional) – Device to store tensors. Defaults to “cpu”.
Examples
>>> arti = Articulation(ArticulationSpec(urdf_or_mjcf_path="assets/robot_description/panda.urdf")) >>> link_poses = arti.forward_kinematics(torch.zeros(1, arti.total_num_dofs), clamp_joint_values=False) >>> torch.allclose(link_poses[0, -1, :3, 3], torch.tensor([0.0880, 0.0000, 0.8676]), atol=1e-3) True