diff --git a/docs/conf.py b/docs/conf.py index 809ec1c28..36367b4cc 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -22,8 +22,8 @@ copyright = "2022, Artificial and Mechanical Intelligence" author = "Artificial and Mechanical Intelligence" -release = "__version__" -version = "main (" + __version__ + ")" +release = f"{__version__}" +version = f"main ({__version__})" # -- General configuration @@ -33,11 +33,16 @@ "sphinx.ext.autodoc", "sphinx.ext.autosummary", "sphinx.ext.intersphinx", - "sphinx_rtd_theme", - "sphinx_autodoc_typehints", "sphinx.ext.mathjax", "sphinx.ext.ifconfig", "sphinx.ext.viewcode", + "sphinx_rtd_theme", + "sphinx.ext.napoleon", + "sphinx_autodoc_typehints", + "sphinx_multiversion", + # "sphinx_fontawesome", + # "breathe", + # "sphinx_tabs.tabs", ] # -- Options for intersphinx extension @@ -50,6 +55,27 @@ exclude_patterns = ["_build"] +autodoc_typehints = "signature" + +# autodoc_default_options = { +# "members": True, +# "undoc-members": True, +# "member-order": "bysource", +# } + +# # Napoleon settings +# napoleon_google_docstring = True +# napoleon_numpy_docstring = True +# napoleon_include_init_with_doc = False +# napoleon_include_private_with_doc = False +# napoleon_include_special_with_doc = False +# napoleon_use_admonition_for_examples = False +# napoleon_use_admonition_for_notes = False +# napoleon_use_admonition_for_references = False +# napoleon_use_ivar = True +# napoleon_use_param = True +# napoleon_use_rtype = True + # -- Options for HTML output html_theme = "sphinx_rtd_theme" diff --git a/docs/index.rst b/docs/index.rst index 224124454..c90c99a21 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -47,6 +47,7 @@ Planned features: modules/parsers modules/simulation modules/utils + modules/typing Credits diff --git a/docs/modules/parsers.rst b/docs/modules/parsers.rst index 17dca62df..e1b159ac9 100644 --- a/docs/modules/parsers.rst +++ b/docs/modules/parsers.rst @@ -6,16 +6,12 @@ Parsers .. automodule:: jaxsim.parsers.descriptions.collision :members: - :inherited-members: .. automodule:: jaxsim.parsers.descriptions.joint :members: - :inherited-members: .. automodule:: jaxsim.parsers.descriptions.link :members: - :inherited-members: .. automodule:: jaxsim.parsers.descriptions.model :members: - :inherited-members: diff --git a/docs/modules/physics.rst b/docs/modules/physics.rst index d91e80fbb..1e06af149 100644 --- a/docs/modules/physics.rst +++ b/docs/modules/physics.rst @@ -14,7 +14,6 @@ Algos .. autofunction:: jaxsim.physics.algos.aba.aba .. autofunction:: jaxsim.physics.algos.crba.crba - .. autofunction:: jaxsim.physics.algos.forward_kinematics.forward_kinematics @@ -34,6 +33,8 @@ Algos :members: :inherited-members: +.. _model: + Model ----- diff --git a/docs/modules/typing.rst b/docs/modules/typing.rst new file mode 100644 index 000000000..fe42d8c3a --- /dev/null +++ b/docs/modules/typing.rst @@ -0,0 +1,35 @@ +.. _typing: + + +Typing +====== + +.. autoclass:: jaxsim.typing.PyTree + :undoc-members: + +.. autoclass:: jaxsim.typing.Tensor + :undoc-members: + +.. autoclass:: jaxsim.typing.Matrix + :undoc-members: + +.. autoclass:: jaxsim.typing.Bool + +.. autoclass:: jaxsim.typing.Int + +.. autoclass:: jaxsim.typing.Float + +.. autoclass:: jaxsim.typing.Vector + :undoc-members: + +.. autoclass:: jaxsim.typing.FloatJax + +.. autoclass:: jaxsim.typing.IntJax + +.. autoclass:: jaxsim.typing.ArrayJax + +.. autoclass:: jaxsim.typing.TensorJax + +.. autoclass:: jaxsim.typing.VectorJax + +.. autoclass:: jaxsim.typing.MatrixJax \ No newline at end of file diff --git a/docs/modules/utils.rst b/docs/modules/utils.rst index 269f5f53d..49470257e 100644 --- a/docs/modules/utils.rst +++ b/docs/modules/utils.rst @@ -6,4 +6,8 @@ Utils .. automodule:: jaxsim.utils :members: - :inherited-members: \ No newline at end of file + :inherited-members: + +.. autoclass:: jaxsim.utils.JaxsimDataclass + :members: + :inherited-members: diff --git a/src/jaxsim/math/skew.py b/src/jaxsim/math/skew.py index 2d0c2d114..eb1163df4 100644 --- a/src/jaxsim/math/skew.py +++ b/src/jaxsim/math/skew.py @@ -6,14 +6,6 @@ class Skew: """ A utility class for skew-symmetric matrix operations. - - Methods: - wedge(vector: jtp.Vector) -> jtp.Matrix: - Compute the skew-symmetric matrix (wedge operator) of a 3D vector. - - vee(matrix: jtp.Matrix) -> jtp.Vector: - Extract the 3D vector from a skew-symmetric matrix (vee operator). - """ @staticmethod diff --git a/src/jaxsim/parsers/descriptions/joint.py b/src/jaxsim/parsers/descriptions/joint.py index 6244e9024..e9e85cb14 100644 --- a/src/jaxsim/parsers/descriptions/joint.py +++ b/src/jaxsim/parsers/descriptions/joint.py @@ -12,7 +12,7 @@ class JointType(enum.IntEnum): """ Enumeration of joint types for robot joints. - Attributes: + Args: F: Fixed joint (no movement). R: Revolute joint (rotation). P: Prismatic joint (translation). @@ -44,7 +44,7 @@ class JointDescriptor: """ Description of a joint type with a specific code. - Attributes: + Args: code (JointType): The code representing the joint type. """ diff --git a/src/jaxsim/parsers/descriptions/link.py b/src/jaxsim/parsers/descriptions/link.py index e6a86897f..2f8a561de 100644 --- a/src/jaxsim/parsers/descriptions/link.py +++ b/src/jaxsim/parsers/descriptions/link.py @@ -24,11 +24,6 @@ class LinkDescription(JaxsimDataclass): parent (Optional[LinkDescription]): The parent link of this link. pose (jtp.Matrix): The pose transformation matrix of the link. children (List[LinkDescription]): List of child links. - - Methods: - lump_with(link: LinkDescription, lumped_H_removed: jtp.Matrix) -> LinkDescription: - Combine the current link with another link, preserving mass and inertia. - """ name: Static[str] diff --git a/src/jaxsim/parsers/descriptions/model.py b/src/jaxsim/parsers/descriptions/model.py index 3421e4131..7e226022f 100644 --- a/src/jaxsim/parsers/descriptions/model.py +++ b/src/jaxsim/parsers/descriptions/model.py @@ -26,13 +26,6 @@ class ModelDescription(KinematicGraph): name (str): The name of the model. fixed_base (bool): Indicates whether the model has a fixed base. collision_shapes (List[CollisionShape]): List of collision shapes associated with the model. - - Methods: - build_model_from(...): Build a model description from provided components. - reduce(...): Reduce the model by removing specified joints. - update_collision_shape_of_link(...): Enable or disable collision shapes associated with a link. - collision_shape_of_link(...): Get the collision shape associated with a specific link. - all_enabled_collidable_points(...): Get all enabled collidable points in the model. """ name: str = None diff --git a/src/jaxsim/physics/algos/aba.py b/src/jaxsim/physics/algos/aba.py index bede3f7c5..c3e9449e2 100644 --- a/src/jaxsim/physics/algos/aba.py +++ b/src/jaxsim/physics/algos/aba.py @@ -1,3 +1,5 @@ +from __future__ import annotations + from typing import Tuple import jax @@ -24,15 +26,15 @@ def aba( Articulated Body Algorithm (ABA) algorithm for forward dynamics. Args: - model (PhysicsModel): The physics model of the articulated body or robot. - xfb (jtp.Vector): The floating base state vector containing quaternion (4D) and position (3D). - q (jtp.Vector): Joint positions (Generalized coordinates). - qd (jtp.Vector): Joint velocities. - tau (jtp.Vector): Joint torques or forces. - f_ext (jtp.Matrix, optional): External forces and torques acting on each link. Defaults to None. + model: The physics model of the articulated body or robot. + xfb: The floating base state vector containing quaternion (4D) and position (3D). + q: Joint positions (Generalized coordinates). + qd: Joint velocities. + tau: Joint torques or forces. + f_ext: External forces and torques acting on each link. Defaults to None. Returns: - Tuple[jtp.Vector, jtp.Vector]: A tuple containing the resulting base acceleration (in inertial-fixed representation) + A tuple containing the resulting base acceleration (in inertial-fixed representation) and joint accelerations. Note: diff --git a/src/jaxsim/physics/algos/soft_contacts.py b/src/jaxsim/physics/algos/soft_contacts.py index 434692d93..c33d169c5 100644 --- a/src/jaxsim/physics/algos/soft_contacts.py +++ b/src/jaxsim/physics/algos/soft_contacts.py @@ -25,16 +25,6 @@ class SoftContactsState: Attributes: tangential_deformation (jtp.Matrix): The tangential deformation of the material at each collidable point. - - Methods: - zero(physics_model: "jaxsim.physics.model.physics_model.PhysicsModel") -> SoftContactsState: - Modify the SoftContactsState instance imposing zero tangential deformation. - - valid(physics_model: "jaxsim.physics.model.physics_model.PhysicsModel") -> bool: - Check if the soft contacts state has valid shape. - - replace(validate: bool = True, kwargs) -> SoftContactsState: - Replace attributes of the soft contacts state. """ tangential_deformation: jtp.Matrix diff --git a/src/jaxsim/physics/model/ground_contact.py b/src/jaxsim/physics/model/ground_contact.py index 7e30cef63..4776cac71 100644 --- a/src/jaxsim/physics/model/ground_contact.py +++ b/src/jaxsim/physics/model/ground_contact.py @@ -20,11 +20,6 @@ class GroundContact: Attributes: point (npt.NDArray): An array of shape (3, N) representing the 3D positions of collidable points. body (Static[npt.NDArray]): An array of integers representing the indices of the bodies (links) associated with each collidable point. - - Methods: - build_from(model_description: ModelDescription) -> GroundContact: - A static method to build a GroundContact object from a ModelDescription instance. - It extracts collidable points' positions and their associated bodies from the model description. """ point: npt.NDArray = dataclasses.field(default_factory=lambda: jnp.array([])) diff --git a/src/jaxsim/physics/model/physics_model.py b/src/jaxsim/physics/model/physics_model.py index 17faf4376..f932a1785 100644 --- a/src/jaxsim/physics/model/physics_model.py +++ b/src/jaxsim/physics/model/physics_model.py @@ -34,40 +34,6 @@ class PhysicsModel(JaxsimDataclass): is_floating_base (Static[bool]): A flag indicating whether the model has a floating base (default: False). gc (GroundContact): The ground contact points of the model (default: empty GroundContact instance). description (Static[jaxsim.parsers.descriptions.model.ModelDescription]): A description of the model (default: None). - - Methods: - build_from( - model_description: jaxsim.parsers.descriptions.model.ModelDescription, - gravity: jtp.Vector = default_gravity() - ) -> PhysicsModel: - Create a PhysicsModel instance from a model description and gravity vector. - - dofs() -> int: - Get the number of degrees of freedom (DOFs) in the model. - - set_gravity(gravity: jtp.Vector) -> None: - Set the gravity vector for the model. - - parent_array() -> jtp.Vector: - Get the parent array (λ(i)) for the model. - - support_body_array(body_index: jtp.Int) -> jtp.Vector: - Get an array of body indices (κ(i)) that support the specified body. - - tree_transforms() -> jtp.Array: - Get an array of tree transforms (pre(i)_X_λ(i)) for all bodies. - - spatial_inertias() -> jtp.Array: - Get an array of spatial inertias (M_links) for all bodies. - - jtype(joint_index: int) -> JointType: - Get the joint type for the specified joint index. - - joint_transforms(q: jtp.Vector) -> jtp.Array: - Compute joint transforms (Xj) for the given joint positions (q). - - motion_subspaces(q: jtp.Vector) -> jtp.Array: - Compute motion subspaces (SS) for the given joint positions (q). """ NB: Static[int] diff --git a/src/jaxsim/physics/model/physics_model_state.py b/src/jaxsim/physics/model/physics_model_state.py index eae4a6072..81d49c777 100644 --- a/src/jaxsim/physics/model/physics_model_state.py +++ b/src/jaxsim/physics/model/physics_model_state.py @@ -21,23 +21,6 @@ class PhysicsModelState(JaxsimDataclass): base_quaternion (jtp.Vector): An array representing the base quaternion (default: [1.0, 0, 0, 0]). base_linear_velocity (jtp.Vector): An array representing the base linear velocity (default: zeros). base_angular_velocity (jtp.Vector): An array representing the base angular velocity (default: zeros). - - Methods: - zero(physics_model: "jaxsim.physics.model.physics_model.PhysicsModel") -> PhysicsModelState: - Create a zero-initialized PhysicsModelState for the given physics model. - - position() -> jtp.Vector: - Get the full state vector, including joint positions, joint velocities, base position, and base quaternion. - - velocity() -> jtp.Vector: - Get the full velocity vector, including base linear velocity, base angular velocity, and joint velocities. - - xfb() -> jtp.Vector: - Get the full state vector in the "xfb" format, which includes base quaternion, base position, base angular - velocity, and base linear velocity. - - valid(physics_model: "jaxsim.physics.model.physics_model.PhysicsModel") -> bool: - Check if the state has valid shapes for the given physics model. """ # Joint state diff --git a/src/jaxsim/simulation/simulator.py b/src/jaxsim/simulation/simulator.py index df412ac76..93adc6cb6 100644 --- a/src/jaxsim/simulation/simulator.py +++ b/src/jaxsim/simulation/simulator.py @@ -1,3 +1,5 @@ +from __future__ import annotations + import dataclasses import functools import pathlib @@ -389,9 +391,9 @@ def step(self, clear_inputs: bool = False) -> Dict[str, StepData]: def step_over_horizon( self, horizon_steps: jtp.Int, - callback_handler: Union["scb.SimulatorCallback", "scb.CallbackHandler"] = None, + callback_handler: Union[scb.SimulatorCallback, scb.CallbackHandler] = None, clear_inputs: jtp.Bool = False, - ) -> Union["JaxSim", Tuple["JaxSim", Tuple["scb.SimulatorCallback", jtp.PyTree]]]: + ) -> Union[JaxSim, Tuple[JaxSim, Tuple[scb.SimulatorCallback, jtp.PyTree]]]: """ Advance the simulation by a given number of steps. diff --git a/src/jaxsim/typing.py b/src/jaxsim/typing.py index 82355cf33..905c0f954 100644 --- a/src/jaxsim/typing.py +++ b/src/jaxsim/typing.py @@ -1,5 +1,4 @@ from typing import Any, Dict, Hashable, List, NamedTuple, Tuple, Union - import jax.numpy as jnp import numpy as np import numpy.typing as npt