fastdev.robo.articulation_spec ============================== .. py:module:: fastdev.robo.articulation_spec Module Contents --------------- .. py:data:: logger .. py:data:: ROOT_JOINT_NAME :type: str :value: '__root__' .. py:class:: Geometry Bases: :py:obj:`abc.ABC` Helper class that provides a standard way to create an ABC using inheritance. .. py:method:: get_trimesh_mesh() -> trimesh.Trimesh :abstractmethod: .. py:class:: Box Bases: :py:obj:`Geometry` Helper class that provides a standard way to create an ABC using inheritance. .. py:attribute:: size :type: List[float] .. py:method:: get_trimesh_mesh() -> trimesh.Trimesh .. py:class:: Cylinder Bases: :py:obj:`Geometry` Helper class that provides a standard way to create an ABC using inheritance. .. py:attribute:: radius :type: float .. py:attribute:: length :type: float .. py:method:: get_trimesh_mesh() -> trimesh.Trimesh .. py:class:: Capsule Bases: :py:obj:`Geometry` Helper class that provides a standard way to create an ABC using inheritance. .. py:attribute:: radius :type: float .. py:attribute:: length :type: float .. py:method:: get_trimesh_mesh() -> trimesh.Trimesh .. py:class:: Sphere Bases: :py:obj:`Geometry` Helper class that provides a standard way to create an ABC using inheritance. .. py:attribute:: radius :type: float .. py:method:: get_trimesh_mesh() -> trimesh.Trimesh .. py:class:: Mesh Bases: :py:obj:`Geometry` Helper class that provides a standard way to create an ABC using inheritance. .. py:attribute:: scale :type: List[float] .. py:attribute:: filename :type: Optional[str] :value: None .. py:attribute:: mesh_dir :type: Optional[str] :value: None .. py:attribute:: is_collision_geometry :type: bool :value: False .. py:attribute:: vertices :type: Optional[numpy.ndarray] :value: None .. py:attribute:: faces :type: Optional[numpy.ndarray] :value: None .. py:method:: get_trimesh_mesh() -> trimesh.Trimesh .. py:class:: Material .. py:attribute:: name :type: Optional[str] :value: None .. py:attribute:: color :type: Optional[numpy.ndarray] :value: None .. py:attribute:: texture :type: Optional[str] :value: None .. py:class:: Visual .. py:attribute:: origin :type: numpy.ndarray .. py:attribute:: geometry :type: Geometry .. py:attribute:: name :type: Optional[str] :value: None .. py:attribute:: material :type: Optional[Material] :value: None .. py:method:: get_trimesh_mesh() -> trimesh.Trimesh .. py:class:: Collision .. py:attribute:: origin :type: numpy.ndarray .. py:attribute:: geometry :type: Geometry .. py:attribute:: name :type: Optional[str] :value: None .. py:method:: get_trimesh_mesh() -> trimesh.Trimesh .. py:class:: JointType(*args, **kwds) Bases: :py:obj:`enum.Enum` Create a collection of name/value pairs. Example enumeration: >>> class Color(Enum): ... RED = 1 ... BLUE = 2 ... GREEN = 3 Access them by: - attribute access: >>> Color.RED - value lookup: >>> Color(1) - name lookup: >>> Color['RED'] Enumerations can be iterated over, and know how many members they have: >>> len(Color) 3 >>> list(Color) [, , ] Methods can be added to enumerations, and members can have their own attributes -- see the documentation for details. .. py:attribute:: ROOT :value: -1 .. py:attribute:: FIXED :value: 0 .. py:attribute:: PRISMATIC :value: 1 .. py:attribute:: REVOLUTE :value: 2 .. py:class:: Joint .. py:attribute:: name :type: str .. py:attribute:: type :type: JointType .. py:attribute:: origin :type: jaxtyping.Float[numpy.ndarray, 4 4] .. py:attribute:: axis :type: jaxtyping.Float[numpy.ndarray, 3] .. py:attribute:: limit :type: Optional[jaxtyping.Float[numpy.ndarray, 2]] .. py:attribute:: parent_link_name :type: str .. py:attribute:: child_link_name :type: str .. py:attribute:: mimic_joint :type: Optional[str] :value: None .. py:attribute:: mimic_multiplier :type: Optional[float] :value: None .. py:attribute:: mimic_offset :type: Optional[float] :value: None .. py:method:: set_child_link_name(child_link_name: str) .. py:method:: __post_init__() .. py:class:: Link .. py:attribute:: name :type: str .. py:attribute:: visuals :type: List[Visual] :value: [] .. py:attribute:: collisions :type: List[Collision] :value: [] .. py:attribute:: joint_name :type: str .. py:method:: set_joint_name(joint_name: str) .. py:method:: get_trimesh_mesh(mode: Literal['visual', 'collision'] = 'collision') -> trimesh.Trimesh .. py:class:: ArticulationSpec(urdf_or_mjcf_path: Union[str, pathlib.Path], mesh_dir: Optional[Union[str, pathlib.Path]] = None, format: Optional[Literal['urdf', 'mjcf']] = None, base_link_name: Optional[str] = None, ee_link_names: Optional[Union[str, List[str]]] = None, mjcf_assets: Optional[Dict[str, Any]] = None, enable_mimic_joints: bool = True) Specification for a single articulation. :param urdf_or_mjcf_path: Path to the URDF or MJCF file. :type urdf_or_mjcf_path: str :param mesh_dir: Directory to store mesh files. Defaults to None. :type mesh_dir: str, optional :param format: Format of the file, either "urdf" or "mjcf". Defaults to None. :type format: str, optional :param mjcf_assets: Assets for MJCF files. Defaults to None. :type mjcf_assets: Dict[str, Any], optional :param enable_mimic_joints: Whether to enable mimic joints. Defaults to True. :type enable_mimic_joints: bool, optional .. rubric:: Examples >>> arti_spec = ArticulationSpec(urdf_or_mjcf_path="assets/robot_description/panda.urdf") >>> arti_spec.num_dofs 8 .. py:attribute:: base_link_name :type: str .. py:attribute:: ee_link_names :type: List[str] .. py:attribute:: link_names :type: List[str] .. py:attribute:: num_links :type: int .. py:attribute:: num_dofs :type: int .. py:attribute:: active_joint_names :type: List[str] .. py:attribute:: has_mimic_joints :type: bool .. py:attribute:: mimic_joint_names :type: List[str] .. py:attribute:: full_joint_names :type: List[str] .. py:attribute:: num_full_joints :type: int .. py:attribute:: urdf_or_mjcf_path :value: '' .. py:attribute:: mesh_dir :value: '' .. py:attribute:: format :value: None .. py:attribute:: mjcf_assets :value: None .. py:attribute:: enable_mimic_joints :value: True .. py:attribute:: num_mimic_joints .. py:method:: parse_urdf() -> Tuple[Dict[str, Joint], Dict[str, Link]] .. py:method:: parse_mjcf() -> Tuple[Dict[str, Joint], Dict[str, Link]] .. py:method:: __repr__() -> str .. py:method:: __str__() -> str .. py:property:: joint_limits :type: Optional[jaxtyping.Float[numpy.ndarray, num_dofs 2]] .. py:property:: mimic_joint_limits :type: Optional[jaxtyping.Float[numpy.ndarray, num_mimic_joints 2]] .. py:property:: mimic_joint_indices :type: jaxtyping.Int[numpy.ndarray, num_mimic_joints] .. py:property:: mimic_multipliers :type: jaxtyping.Float[numpy.ndarray, num_mimic_joints] .. py:property:: mimic_offsets :type: jaxtyping.Float[numpy.ndarray, num_mimic_joints] .. py:property:: link_joint_indices :type: jaxtyping.Int[numpy.ndarray, num_links] .. py:property:: link_indices_topological_order :type: jaxtyping.Int[numpy.ndarray, num_links] .. py:property:: parent_link_indices :type: jaxtyping.Int[numpy.ndarray, num_links] .. py:property:: link_joint_axes :type: Optional[jaxtyping.Float[numpy.ndarray, num_links 3]] .. py:property:: full_joint_axes :type: jaxtyping.Float[numpy.ndarray, num_full_joints 3] .. py:property:: link_joint_origins :type: jaxtyping.Float[numpy.ndarray, num_links 4 4] .. py:property:: link_joint_types :type: jaxtyping.Int[numpy.ndarray, num_links] .. py:method:: get_ancestor_links_mask(link_name_or_idx: Union[str, int]) -> jaxtyping.Int[numpy.ndarray, num_links] .. py:method:: get_link_trimesh_meshes(mode: Literal['visual', 'collision'] = 'collision', return_empty_meshes: bool = True) -> Dict[str, trimesh.Trimesh]