Skip to content

Commit

Permalink
Merge branch 'ami-iit:main' into feature/docs
Browse files Browse the repository at this point in the history
  • Loading branch information
flferretti authored Oct 4, 2023
2 parents 5dd25b7 + 6397508 commit 799eb60
Show file tree
Hide file tree
Showing 5 changed files with 29 additions and 23 deletions.
4 changes: 1 addition & 3 deletions .github/workflows/ci_cd.yml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ jobs:
- name: Set up Python
uses: actions/setup-python@v4
with:
python-version: 3.8
python-version: "3.10"

- name: Install Python tools
run: pip install build twine
Expand Down Expand Up @@ -58,8 +58,6 @@ jobs:
# https://github.com/google/jax/issues/5795
# - windows-latest
python:
- "3.8"
- "3.9"
- "3.10"
- "3.11"

Expand Down
4 changes: 1 addition & 3 deletions setup.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,6 @@ classifiers =
Operating System :: POSIX :: Linux
Operating System :: MacOS
Operating System :: Microsoft
Programming Language :: Python :: 3.8
Programming Language :: Python :: 3.9
Programming Language :: Python :: 3.10
Programming Language :: Python :: 3.11
Programming Language :: Python :: 3 :: Only
Expand All @@ -52,7 +50,7 @@ zip_safe = False
packages = find:
package_dir =
=src
python_requires = >=3.8
python_requires = >=3.10
install_requires =
coloredlogs
jax >= 0.4.1
Expand Down
6 changes: 4 additions & 2 deletions src/jaxsim/high_level/model.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import jax.numpy as jnp
import jax_dataclasses
import numpy as np
import rod
from jax_dataclasses import Static

import jaxsim.physics.algos.aba
Expand Down Expand Up @@ -125,7 +126,7 @@ class Model(JaxsimDataclass):

@staticmethod
def build_from_model_description(
model_description: Union[str, pathlib.Path],
model_description: Union[str, pathlib.Path, rod.Model],
model_name: Optional[str] = None,
vel_repr: VelRepr = VelRepr.Mixed,
gravity: jtp.Array = jaxsim.physics.default_gravity(),
Expand All @@ -136,7 +137,8 @@ def build_from_model_description(
Build a Model object from a model description.
Args:
model_description: Either a path to a file or a string containing the URDF/SDF description.
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
32 changes: 19 additions & 13 deletions src/jaxsim/parsers/rod/parser.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,16 @@ class SDFData(NamedTuple):


def extract_model_data(
model_description: Union[pathlib.Path, str],
model_description: Union[pathlib.Path, str, rod.Model],
model_name: Optional[str] = None,
is_urdf: Optional[bool] = None,
) -> SDFData:
"""
Extract data from an SDF/URDF resource useful to build a JaxSim model.
Args:
model_description: Either a path to an SDF/URDF file or a string containing its content.
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 name of the model to extract from the SDF resource.
is_urdf: Whether the SDF resource is a URDF file. Needed only if model_description
is a URDF string.
Expand All @@ -49,17 +50,20 @@ def extract_model_data(
The extracted model data.
"""

# Parse the SDF resource
sdf_element = rod.Sdf.load(sdf=model_description, is_urdf=is_urdf)
if isinstance(model_description, rod.Model):
sdf_model = model_description
else:
# Parse the SDF resource
sdf_element = rod.Sdf.load(sdf=model_description, is_urdf=is_urdf)

if len(sdf_element.models()) == 0:
raise RuntimeError("Failed to find any model in SDF resource")
if len(sdf_element.models()) == 0:
raise RuntimeError("Failed to find any model in SDF resource")

# Assume the SDF resource has only one model, or the desired model name is given
sdf_models = {m.name: m for m in sdf_element.models()}
sdf_model = (
sdf_element.models()[0] if len(sdf_models) == 1 else sdf_models[model_name]
)
# Assume the SDF resource has only one model, or the desired model name is given
sdf_models = {m.name: m for m in sdf_element.models()}
sdf_model = (
sdf_element.models()[0] if len(sdf_models) == 1 else sdf_models[model_name]
)

# Log model name
logging.debug(msg=f"Found model '{sdf_model.name}' in SDF resource")
Expand Down Expand Up @@ -298,13 +302,15 @@ def extract_model_data(


def build_model_description(
model_description: Union[pathlib.Path, str], is_urdf: Optional[bool] = False
model_description: Union[pathlib.Path, str, rod.Model],
is_urdf: Optional[bool] = False,
) -> descriptions.ModelDescription:
"""
Builds a model description from an SDF/URDF resource.
Args:
model_description: Either a path to an SDF/URDF file or a string containing its content.
model_description: A path to an SDF/URDF file, a string containing its content,
or a pre-parsed/pre-built rod model.
is_urdf: Whether the SDF resource is a URDF file. Needed only if model_description
is a URDF string.
Returns:
Expand Down
6 changes: 4 additions & 2 deletions src/jaxsim/simulation/simulator.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import jax
import jax.numpy as jnp
import jax_dataclasses
import rod
from jax_dataclasses import Static

import jaxsim.high_level
Expand Down Expand Up @@ -226,15 +227,16 @@ def set_gravity(self, gravity: jtp.Vector) -> None:

def insert_model_from_description(
self,
model_description: Union[pathlib.Path, str],
model_description: Union[pathlib.Path, str, rod.Model],
model_name: Optional[str] = None,
considered_joints: Optional[List[str]] = None,
) -> Model:
"""
Insert a model from a model description.
Args:
model_description: Either a path to a file or a string containing the URDF/SDF description.
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 799eb60

Please sign in to comment.