Skip to content

Commit

Permalink
Fix format and warnings for docs
Browse files Browse the repository at this point in the history
  • Loading branch information
flferretti committed Oct 4, 2023
1 parent 193c80e commit 4039df1
Show file tree
Hide file tree
Showing 21 changed files with 66 additions and 19 deletions.
2 changes: 1 addition & 1 deletion docs/conf.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# Configuration file for the Sphinx documentation builder.
import os
import pathlib
import sys
import os

# -- Version information

Expand Down
3 changes: 1 addition & 2 deletions src/jaxsim/high_level/model.py
Original file line number Diff line number Diff line change
Expand Up @@ -137,8 +137,7 @@ def build_from_model_description(
Build a Model object from a model description.
Args:
model_description: A path to an SDF/URDF file, a string containing its content,
or a pre-parsed/pre-built rod model.
model_description: A path to an SDF/URDF file, a string containing its content, or a pre-parsed/pre-built rod model.
model_name: The optional name of the model that overrides the one in the description.
vel_repr: The velocity representation to use.
gravity: The 3D gravity vector.
Expand Down
3 changes: 3 additions & 0 deletions src/jaxsim/math/adjoint.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,12 @@
import jax.numpy as jnp

import jaxsim.typing as jtp
from jaxsim.sixd import so3

from .quaternion import Quaternion
from .skew import Skew


class Adjoint:
@staticmethod
def from_quaternion_and_translation(
Expand Down
3 changes: 3 additions & 0 deletions src/jaxsim/math/conv.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
import jax.numpy as jnp

import jaxsim.typing as jtp

from .skew import Skew


class Convert:
@staticmethod
def coordinates_tf(X: jtp.Matrix, p: jtp.Matrix) -> jtp.Matrix:
Expand Down
3 changes: 3 additions & 0 deletions src/jaxsim/math/cross.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
import jax.numpy as jnp

import jaxsim.typing as jtp

from .skew import Skew


class Cross:
@staticmethod
def vx(velocity_sixd: jtp.Vector) -> jtp.Matrix:
Expand Down
4 changes: 4 additions & 0 deletions src/jaxsim/math/inertia.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,12 @@
from typing import Tuple

import jax.numpy as jnp

import jaxsim.typing as jtp

from .skew import Skew


class Inertia:
@staticmethod
def to_sixd(mass: jtp.Float, com: jtp.Vector, I: jtp.Matrix) -> jtp.Matrix:
Expand Down
4 changes: 4 additions & 0 deletions src/jaxsim/math/joint.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@
from typing import Tuple, Union

import jax.numpy as jnp

import jaxsim.typing as jtp
from jaxsim.parsers.descriptions import JointDescriptor, JointGenericAxis, JointType

from .adjoint import Adjoint
from .rotation import Rotation


def jcalc(
jtyp: Union[JointType, JointDescriptor], q: jtp.Float
) -> Tuple[jtp.Matrix, jtp.Vector]:
Expand Down
2 changes: 2 additions & 0 deletions src/jaxsim/math/quaternion.py
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
import jax.lax
import jax.numpy as jnp

import jaxsim.typing as jtp
from jaxsim.sixd import so3


class Quaternion:
@staticmethod
def to_xyzw(wxyz: jtp.Vector) -> jtp.Vector:
Expand Down
4 changes: 4 additions & 0 deletions src/jaxsim/math/rotation.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@
from typing import Tuple

import jax
import jax.numpy as jnp

import jaxsim.typing as jtp
from jaxsim.sixd import so3

from .skew import Skew


class Rotation:
@staticmethod
def x(theta: jtp.Float) -> jtp.Matrix:
Expand Down
2 changes: 2 additions & 0 deletions src/jaxsim/math/skew.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
import jax.numpy as jnp

import jaxsim.typing as jtp


class Skew:
"""
A utility class for skew-symmetric matrix operations.
Expand Down
4 changes: 4 additions & 0 deletions src/jaxsim/parsers/descriptions/collision.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

from .link import LinkDescription


@dataclasses.dataclass
class CollidablePoint:
"""
Expand Down Expand Up @@ -58,6 +59,7 @@ def __str__(self):
+ ")"
)


@dataclasses.dataclass
class CollisionShape(abc.ABC):
"""
Expand All @@ -78,6 +80,7 @@ def __str__(self):
+ "\n])"
)


@dataclasses.dataclass
class BoxCollision(CollisionShape):
"""
Expand All @@ -90,6 +93,7 @@ class BoxCollision(CollisionShape):

center: npt.NDArray


@dataclasses.dataclass
class SphereCollision(CollisionShape):
"""
Expand Down
6 changes: 5 additions & 1 deletion src/jaxsim/parsers/descriptions/joint.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@

from .link import LinkDescription


class JointType(enum.IntEnum):
"""
Enumeration of joint types for robot joints.
Expand All @@ -31,12 +32,13 @@ class JointType(enum.IntEnum):
Rx = enum.auto()
Ry = enum.auto()
Rz = enum.auto()

# Prismatic joints, single axis
Px = enum.auto()
Py = enum.auto()
Pz = enum.auto()


@dataclasses.dataclass
class JointDescriptor:
"""
Expand All @@ -52,6 +54,7 @@ class JointDescriptor:
def __hash__(self) -> int:
return hash(self.__repr__())


@dataclasses.dataclass
class JointGenericAxis(JointDescriptor):
"""
Expand All @@ -74,6 +77,7 @@ def __eq__(self, other):
def __hash__(self) -> int:
return hash(self.__repr__())


@dataclasses.dataclass
class JointDescription:
"""
Expand Down
1 change: 1 addition & 0 deletions src/jaxsim/parsers/descriptions/link.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
from jaxsim.sixd import se3
from jaxsim.utils import JaxsimDataclass


@jax_dataclasses.pytree_dataclass
class LinkDescription(JaxsimDataclass):
"""
Expand Down
7 changes: 4 additions & 3 deletions src/jaxsim/parsers/descriptions/model.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,15 @@
from typing import List

import numpy.typing as npt

import jaxsim.logging as logging

from ..kinematic_graph import KinematicGraph, RootPose
from .collision import CollidablePoint, CollisionShape
from .joint import JointDescription
from .link import LinkDescription


@dataclasses.dataclass(frozen=True)
class ModelDescription(KinematicGraph):
"""
Expand All @@ -30,7 +33,6 @@ class ModelDescription(KinematicGraph):
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
Expand Down Expand Up @@ -66,7 +68,6 @@ def build_model_from(
Raises:
ValueError: If invalid or missing input data.
"""

# Create the full kinematic graph
Expand Down Expand Up @@ -164,8 +165,8 @@ def reduce(self, considered_joints: List[str]) -> "ModelDescription":
Raises:
ValueError: If the specified joints are not part of the model.
"""

msg = "The model reduction logic assumes that removed joints have zero angles"
logging.info(msg=msg)

Expand Down
1 change: 1 addition & 0 deletions src/jaxsim/parsers/kinematic_graph.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ class RootPose(NamedTuple):
root_position (npt.NDArray): A NumPy array of shape (3,) representing the root's position.
root_quaternion (npt.NDArray): A NumPy array of shape (4,) representing the root's quaternion.
"""

root_position: npt.NDArray = np.zeros(3)
root_quaternion: npt.NDArray = np.array([1.0, 0, 0, 0])

Expand Down
2 changes: 1 addition & 1 deletion src/jaxsim/physics/algos/crba.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ def crba(model: PhysicsModel, q: jtp.Vector) -> jtp.Matrix:
Returns:
jtp.Matrix: The Composite Rigid-Body Inertia Matrix (CRBA) of the articulated body or robot.
"""

_, q, _, _, _, _ = utils.process_inputs(
physics_model=model, xfb=None, q=q, qd=None, tau=None, f_ext=None
)
Expand Down
2 changes: 1 addition & 1 deletion src/jaxsim/physics/algos/forward_kinematics.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ def forward_kinematics_model(
Returns:
jtp.Array: A 3D array containing the forward kinematics transformations for all links.
"""

x_fb, q, _, _, _, _ = utils.process_inputs(
physics_model=model, xfb=xfb, q=q, qd=None, tau=None, f_ext=None
)
Expand Down
22 changes: 18 additions & 4 deletions src/jaxsim/physics/algos/soft_contacts.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,22 @@

@jax_dataclasses.pytree_dataclass
class SoftContactsState:
"""State of the soft contacts model."""
"""
State of the soft contacts model.
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

Expand All @@ -37,7 +52,7 @@ def zero(
Returns:
SoftContactsState: A SoftContactsState instance with zero tangential deformation.
"""

return SoftContactsState(
tangential_deformation=jnp.zeros(shape=(3, physics_model.gc.body.size))
)
Expand All @@ -54,7 +69,7 @@ def valid(
Returns:
bool: True if the state has a valid shape, otherwise False.
"""

from jaxsim.simulation.utils import check_valid_shape

return check_valid_shape(
Expand All @@ -70,7 +85,6 @@ def replace(self, validate: bool = True, **kwargs) -> "SoftContactsState":
Args:
validate (bool, optional): Whether to validate the state after replacement. Defaults to True.
**kwargs: Keyword arguments for attribute replacement.
Returns:
SoftContactsState: A new SoftContactsState instance with replaced attributes.
Expand Down
4 changes: 2 additions & 2 deletions src/jaxsim/physics/algos/terrain.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,6 @@ def height(self, x: float, y: float) -> float:
Returns:
float: The height of the terrain at the specified location on the plane.
"""

a, b, c = self.plane_normal
return -(a * x + b * x) / c
return -(a * x + b * x) / c
3 changes: 1 addition & 2 deletions src/jaxsim/physics/model/ground_contact.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,7 @@ 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.
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:
Expand Down
3 changes: 1 addition & 2 deletions src/jaxsim/simulation/simulator.py
Original file line number Diff line number Diff line change
Expand Up @@ -235,8 +235,7 @@ def insert_model_from_description(
Insert a model from a model description.
Args:
model_description: A path to an SDF/URDF file, a string containing its content,
or a pre-parsed/pre-built rod model.
model_description: A path to an SDF/URDF file, a string containing its content, or a pre-parsed/pre-built rod model.
model_name: The optional name of the model that overrides the one in the description.
considered_joints: Optional list of joints to consider. It is also useful to specify the joint serialization.
Expand Down

0 comments on commit 4039df1

Please sign in to comment.