-
Notifications
You must be signed in to change notification settings - Fork 11
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Finalize the functional APIs and replace the OOP classes #108
Merged
Merged
Changes from all commits
Commits
Show all changes
172 commits
Select commit
Hold shift + click to select a range
688664b
Remove existing tests of OOP APIs
diegoferigo 1b506de
Add a pytest fixture to generate a PRNG key
diegoferigo ff02a33
Add fixture to parameterize tests over all velocity representations
diegoferigo d70568c
Add session-wide fixtures to provide tested models
diegoferigo 020ff88
Add collections of tested models
diegoferigo 43fa2f9
Add tests of jaxsim.api.data module
diegoferigo 5cdd914
Add test of jaxsim.api.joint module
diegoferigo 446369a
Add test of jaxsim.api.link module
diegoferigo d95b589
Add test of jaxsim.api.model module
diegoferigo 29ec058
Add methods to wrapper utils_idyntree.KinDynComputations
diegoferigo 9b49549
Add other iDynTree testing helpers
diegoferigo 97e54d6
Add test to check automatic differentiation of algorithms
diegoferigo b977b92
Fix random generation of JaxSimModelData for fixed-base models
diegoferigo 8314788
Fix random generation of JaxSimModelData for jointless models
diegoferigo ccc3473
Fix api.joint.name_to_idx
diegoferigo 0932028
Fix ABA in Mixed representation for fixed-base models
diegoferigo c234320
Fix ABA when inputs are passed
diegoferigo 196426c
Fix computation of bias forces for fixed-base models
diegoferigo 5eeda35
Rename Heun integrator to Heun2
diegoferigo f4563bf
Fix ForwardEuler integrator
diegoferigo b81bc1d
Fix shape correction of the Butcher tableau b parameter
diegoferigo 945f04b
Fix non-jit execution of RBDAs for models with no joints
diegoferigo 1b35ea2
Fix collidable_points_pos_vel for models with no collidable points
diegoferigo d7f1317
Remove pytest-forked
diegoferigo 9612045
Require updated version of the rod dependency
diegoferigo e96595b
Fix joint.position_limit for jointless models
diegoferigo 7a4e1ce
Fix cast of gc.body in api.ode
diegoferigo 75cd229
Do not raise in simulation.utils.check_valid_shape
diegoferigo c7c8644
Increase tolerance in test of reduced CoM position
diegoferigo 866a6e3
Update api.__init__.py
diegoferigo 2b4c2c5
Add again support for latest jax and jaxlib
diegoferigo 6397446
Install Gazebo Sim instead of Gazebo Classic in CI
diegoferigo 67486e0
Add test of jit compiling functions taking JaxSimModel as input
diegoferigo 5dcfeb9
Use ordered split keys in random data generation
diegoferigo a54bfae
Do not alter during runtime Butcher tableau coefficients
diegoferigo 795df2b
Merge pull request #106 from ami-iit/functional_tests
diegoferigo 6af0f84
Add KinDynParameters class
diegoferigo ef49d90
Add JointModel class
diegoferigo 3179a80
Update JaxSimModel to store KinDynParameters
diegoferigo 6b7f0bf
Uniform imports of jaxsim.api package
diegoferigo cae2d6e
Import KinDynParameters into jaxsim.api package
diegoferigo c153917
Update api.joint to use KinDynParameters instead of PhysicsModel
diegoferigo e3b5816
Update api.link to use KinDynParameters instead of PhysicsModel
diegoferigo 57875b6
Add missing docstrings
diegoferigo 67d2d12
Update dataclass properties of JaxSimModel attributes
diegoferigo d7466e5
Build KinDynParameters from parsed ModelDescription
diegoferigo 9eaeac1
Add HashlessObject class
diegoferigo 6e2a2e1
Store ModelDescription directly inside JaxSimModel
diegoferigo 20a77c2
Update GroundContact class
diegoferigo 4bfc629
Store ContactParameters inside KinDynParameters
diegoferigo 85d432a
Propagate axes change of GroundContact
diegoferigo 87c47c6
Define DoFs of base link
diegoferigo 756b69f
Update api.ode to use KinDynParameters instead of PhysicsModel
diegoferigo 7b6a88b
Apply suggestions from code review
diegoferigo 1dbd1c8
Merge pull request #101 from ami-iit/feature/kin_dyn_parameters
diegoferigo 53b801e
Update soft_contacts to use KinDynParameters instead of PhysicsModel
diegoferigo bebb581
Prepare transition to jaxsim.api from jaxsim.{high_level|physics}
diegoferigo 58ada61
Update PhysicsModel{Input|State}, ODE{Input|State}, SoftContactsState
diegoferigo 3d54ee8
Use new builder methods of ODEState and ODEInput
diegoferigo 7426bcb
Introduce and propagate StandardGravity
diegoferigo 3ad74e2
Disable some exception while tracing
diegoferigo a1fac84
Move rigid-body dynamics algorithms to jaxsim.rbda package
diegoferigo 0c1170e
Move terrain definitions to jaxsim.terrain package
diegoferigo 1967b7b
Move data structures to jaxsim.api.ode_data
diegoferigo 05f2fa0
Update AD test
diegoferigo d0e7298
Import math resources in parent package
diegoferigo 5b8594c
Update rbda.utils.process_inputs to new APIs
diegoferigo 802e3c3
Add model.link_spatial_inertia_matrices
diegoferigo 3227144
Compute tree transforms considering also the base pose
diegoferigo b8c2a87
Update ABA formulation to new APIs
diegoferigo f4f58a9
Normalize quaternion in JaxSimModelData.base_orientation
diegoferigo 9ce2e20
Fix AD test with normalized quaternions
diegoferigo 99f2353
Normalize quaternion before computing its derivative
diegoferigo 8db9c57
Update CRBA formulation to new APIs
diegoferigo 2c13931
Update FK to new APIs
diegoferigo 7c86c4a
Update RNEA to new APIs
diegoferigo fd76844
Update Jacobian to new APIs
diegoferigo 507167a
Update test_ad_integration
diegoferigo ef51c17
Normalize quaternion also in RK stages of SO(3) integrators
diegoferigo 0e7eec7
Update SoftContacts to new APIs
diegoferigo 2e7c50f
Minor updates of soft contacts algorithm
diegoferigo 93985fb
Remove deprecated PhysicsModel from JaxSimModel
diegoferigo 5cf468b
Remove unused methods from PhysicsModelState
diegoferigo b1d6755
Update import in api.references
diegoferigo e5ce67a
Move GroundContact to kin_dyn_parameters.ContactParams
diegoferigo 1b4a528
Transpose the tangential deformation to have the points as first axis
diegoferigo 900ea0d
Move StandardGravity to jaxsim.math
diegoferigo ca32a7e
Merge pull request #112 from ami-iit/transition_to_functional
diegoferigo ace54c6
Make mutability check in JaxsimDataclass.mutable_context stricter
diegoferigo 0fcaede
Update typing of context managers
diegoferigo dc3119a
Do not automatically copy replaced fields
diegoferigo 7f9b33a
Add explicit flatten_fn and unflatten_fn
diegoferigo 41166b8
Minor enhancement in editable method
diegoferigo adf63b0
Update mutability handling
diegoferigo 6f0343c
Add docstrings
diegoferigo 2ca7bd8
Add JaxsimDataclass.check_compatibility helper
diegoferigo 83fa95c
JaxsimDataclass.replace returns a shallow copy of the original object
diegoferigo eb4bc01
Merge pull request #116 from ami-iit/improve_jaxsim_dataclass
diegoferigo 897197c
Add base class of embedded Runge-Kutta schemes
diegoferigo 9dbbb17
Add HeunEulerSO3 and BogackiShampineSO3 variable-step integrators
diegoferigo b0a4a30
Fix conversion to nanoseconds in ode closure
diegoferigo ed4c6ff
Fix Butcher tableau of Heun integrator
diegoferigo 6d91fc5
Introduce different stages to initialize integrators
diegoferigo b177ead
Add Quaternion.integration to integrate quaternions on SO(3)
diegoferigo 1d2049f
Integrate quaternions in SO(3) also in RK stages
diegoferigo f8aaa7c
Move ExplicitRungeKuttaSO3Mixin to integrators.common
diegoferigo a5be7b4
Merge pull request #115 from ami-iit/variable_step_integrators
diegoferigo 7f4cb56
Update imports
diegoferigo 3a6906e
Fix check in data
diegoferigo 53be994
Move functions related to CoM to new jaxsim.api.com module
diegoferigo 16d996c
Add new test for api.com module
diegoferigo 8f8888b
Add new methods to iDynTree wrapper
diegoferigo 44e3dfa
Add api.link.velocity
diegoferigo d874908
Add api.link.velocity test
diegoferigo c86484e
Update api.link with minor changes and docstrings
diegoferigo 763d664
Update api.model with minor changes
diegoferigo f36f7a2
Add model.total_momentum_jacobian
diegoferigo 736b1a1
Add model.locked_spatial_inertia
diegoferigo ae81cfe
Add com.locked_centroidal_spatial_inertia
diegoferigo c3e0457
Add com.centroidal_momentum_jacobian
diegoferigo 4f22a3e
Add com.centroidal_momentum
diegoferigo d8bc720
Add com.average_centroidal_velocity_jacobian
diegoferigo a2f891c
Add com.average_centroidal_velocity
diegoferigo 5fb9e17
Add com.com_linear_velocity
diegoferigo 83b28bc
Add model.average_velocity_jacobian
diegoferigo 8fd3f1a
Add model.average_velocity
diegoferigo 82a8f8f
Test new api.model functions
diegoferigo 957caa8
Test new api.com functions
diegoferigo 5d74bfb
Add math.transform module
diegoferigo 6837a79
Add Adjoint.from_transform method
diegoferigo d0e3b85
Add contact.collidable_point_dynamics
diegoferigo 89a813f
Add contact.collidable_point_forces
diegoferigo 680a343
Add model.link_contact_forces
diegoferigo 45d37b0
Update ode.system_velocity_dynamics to use new contact function
diegoferigo e1c9175
Merge pull request #117 from ami-iit/extend_functional_apis
diegoferigo f123b57
Add support for randomizing standard_gravity in random_model_data
diegoferigo 154e3b8
Update JaxsimDataclass.replace method to use dataclasses.replace
diegoferigo 43587dc
Fix wrap_system_dynamics_for_integration
diegoferigo 6e5779d
Fix `api.contact.in_contact`
flferretti 48328e8
Cast RBDA inputs to float
diegoferigo ba073e3
Make SoftContactsParams inherit fro JaxsimDataclass
diegoferigo 227ed00
Add integrator_kwargs argument to api.model.step
diegoferigo 6128860
Allow reducing a model and remove all joints
diegoferigo dd0d00b
Address review
flferretti 074012c
Add new jacobian_full_doubly_left RBDA
diegoferigo 31ee91f
Merge pull request #119 from ami-iit/flferretti-patch-1
flferretti 535fe70
Update model.generalized_free_floating_jacobian to use the doubly-left
diegoferigo 18f9553
Update link.jacobian to use the new doubly-left jacobian
diegoferigo ecdf60c
Merge pull request #121 from ami-iit/optimize_jacobian_algo
diegoferigo b65fa47
Update docstrings of JointModel
diegoferigo 075ea39
Fix error in KynDynParameters.set_link_inertia
diegoferigo 782c8b0
Add JointParameters.index
diegoferigo ee387bc
Add LinkParameters.index
diegoferigo 869c7a8
Create a dummy JointParameters for joint-less models
diegoferigo b8c4d78
Move creation of contact parameters
diegoferigo cc6939f
Propagate missing base transform argument
diegoferigo fbd98cb
Minor changes with docstring and comments updates
diegoferigo ae7cc6d
Update hash computation
diegoferigo 43a4aed
Merge pull request #120 from ami-iit/enhance_parametric_models
diegoferigo 729b126
Remove jaxsim.simulation package
diegoferigo 58f2890
Remove jaxsim.physics package
diegoferigo eca753d
remove jaxsim.high_level package
diegoferigo ed10470
Remove unused modules from jaxsim.math package
diegoferigo 14e99b5
Remove unused modules from jaxsim.utils
diegoferigo 1635366
Merge pull request #123 from ami-iit/remove_oop_and_unused_code
diegoferigo 8ea1a0b
Avoid unhashable args in `contact.in_contact`
flferretti 0968790
Allow importing `Self` from `typing_extensions`
flferretti 0aa153d
Rename external_forces to link_forces
diegoferigo 7220b7a
Remove unused jaxsim.math.joint
diegoferigo 569afdc
Unify ε definition used to compute finite differences in AD test
diegoferigo 07e4642
Use default tolerance in integration AD test with SO(3) integrators
diegoferigo 2b353d1
Test AD of soft contacts model also including its parameters
diegoferigo File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change | ||||
---|---|---|---|---|---|---|
|
@@ -61,7 +61,6 @@ def _is_editable() -> bool: | |||||
del _np_options | ||||||
del _is_editable | ||||||
|
||||||
from . import high_level, logging, math, simulation, sixd | ||||||
from .high_level.common import VelRepr | ||||||
from .simulation.ode_integration import IntegratorType | ||||||
from .simulation.simulator import JaxSim | ||||||
from . import terrain # isort:skip | ||||||
from . import api, integrators, logging, math, rbda | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Reimporting
Suggested change
|
||||||
from .api.common import VelRepr |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1 +1,3 @@ | ||
from . import contact, data, joint, link, model, ode | ||
from . import common # isort:skip | ||
from . import model, data # isort:skip | ||
from . import com, contact, joint, kin_dyn_parameters, link, ode, ode_data, references |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,240 @@ | ||
import jax | ||
import jax.numpy as jnp | ||
import jaxlie | ||
|
||
import jaxsim.api as js | ||
import jaxsim.math | ||
import jaxsim.typing as jtp | ||
|
||
from .common import VelRepr | ||
|
||
|
||
@jax.jit | ||
def com_position( | ||
model: js.model.JaxSimModel, data: js.data.JaxSimModelData | ||
) -> jtp.Vector: | ||
""" | ||
Compute the position of the center of mass of the model. | ||
Args: | ||
model: The model to consider. | ||
data: The data of the considered model. | ||
Returns: | ||
The position of the center of mass of the model w.r.t. the world frame. | ||
""" | ||
|
||
m = js.model.total_mass(model=model) | ||
|
||
W_H_L = js.model.forward_kinematics(model=model, data=data) | ||
W_H_B = data.base_transform() | ||
B_H_W = jaxlie.SE3.from_matrix(W_H_B).inverse().as_matrix() | ||
|
||
def B_p̃_LCoM(i) -> jtp.Vector: | ||
m = js.link.mass(model=model, link_index=i) | ||
L_p_LCoM = js.link.com_position( | ||
model=model, data=data, link_index=i, in_link_frame=True | ||
) | ||
return m * B_H_W @ W_H_L[i] @ jnp.hstack([L_p_LCoM, 1]) | ||
|
||
com_links = jax.vmap(B_p̃_LCoM)(jnp.arange(model.number_of_links())) | ||
|
||
B_p̃_CoM = (1 / m) * com_links.sum(axis=0) | ||
B_p̃_CoM = B_p̃_CoM.at[3].set(1) | ||
|
||
return (W_H_B @ B_p̃_CoM)[0:3].astype(float) | ||
|
||
|
||
@jax.jit | ||
def com_linear_velocity( | ||
model: js.model.JaxSimModel, data: js.data.JaxSimModelData | ||
) -> jtp.Vector: | ||
r""" | ||
Compute the linear velocity of the center of mass of the model. | ||
Args: | ||
model: The model to consider. | ||
data: The data of the considered model. | ||
Returns: | ||
The linear velocity of the center of mass of the model in the | ||
active representation. | ||
Note: | ||
The linear velocity of the center of mass is expressed in the mixed frame | ||
:math:`G = ({}^W \mathbf{p}_{\text{CoM}}, [C])`, where :math:`[C] = [W]` if the | ||
active velocity representation is either inertial-fixed or mixed, | ||
and :math:`[C] = [B]` if the active velocity representation is body-fixed. | ||
""" | ||
|
||
# Extract the linear component of the 6D average centroidal velocity. | ||
# This is expressed in G[B] in body-fixed representation, and in G[W] in | ||
# inertial-fixed or mixed representation. | ||
G_vl_WG = average_centroidal_velocity(model=model, data=data)[0:3] | ||
|
||
return G_vl_WG | ||
|
||
|
||
@jax.jit | ||
def centroidal_momentum( | ||
model: js.model.JaxSimModel, data: js.data.JaxSimModelData | ||
) -> jtp.Vector: | ||
r""" | ||
Compute the centroidal momentum of the model. | ||
Args: | ||
model: The model to consider. | ||
data: The data of the considered model. | ||
Returns: | ||
The centroidal momentum of the model. | ||
Note: | ||
The centroidal momentum is expressed in the mixed frame | ||
:math:`({}^W \mathbf{p}_{\text{CoM}}, [C])`, where :math:`C = W` if the | ||
active velocity representation is either inertial-fixed or mixed, | ||
and :math:`C = B` if the active velocity representation is body-fixed. | ||
""" | ||
|
||
ν = data.generalized_velocity() | ||
G_J = centroidal_momentum_jacobian(model=model, data=data) | ||
|
||
return G_J @ ν | ||
|
||
|
||
@jax.jit | ||
def centroidal_momentum_jacobian( | ||
model: js.model.JaxSimModel, data: js.data.JaxSimModelData | ||
) -> jtp.Matrix: | ||
r""" | ||
Compute the Jacobian of the centroidal momentum of the model. | ||
Args: | ||
model: The model to consider. | ||
data: The data of the considered model. | ||
Returns: | ||
The Jacobian of the centroidal momentum of the model. | ||
Note: | ||
The frame corresponding to the output representation of this Jacobian is either | ||
:math:`G[W]`, if the active velocity representation is inertial-fixed or mixed, | ||
or :math:`G[B]`, if the active velocity representation is body-fixed. | ||
Note: | ||
This Jacobian is also known in the literature as Centroidal Momentum Matrix. | ||
""" | ||
|
||
# Compute the Jacobian of the total momentum with body-fixed output representation. | ||
# We convert the output representation either to G[W] or G[B] below. | ||
B_Jh = js.model.total_momentum_jacobian( | ||
model=model, data=data, output_vel_repr=VelRepr.Body | ||
) | ||
|
||
W_H_B = data.base_transform() | ||
B_H_W = jaxsim.math.Transform.inverse(W_H_B) | ||
|
||
W_p_CoM = com_position(model=model, data=data) | ||
|
||
match data.velocity_representation: | ||
case VelRepr.Inertial | VelRepr.Mixed: | ||
W_H_G = W_H_GW = jnp.eye(4).at[0:3, 3].set(W_p_CoM) | ||
case VelRepr.Body: | ||
W_H_G = W_H_GB = W_H_B.at[0:3, 3].set(W_p_CoM) | ||
case _: | ||
raise ValueError(data.velocity_representation) | ||
|
||
# Compute the transform for 6D forces. | ||
G_Xf_B = jaxsim.math.Adjoint.from_transform(transform=B_H_W @ W_H_G).T | ||
|
||
return G_Xf_B @ B_Jh | ||
|
||
|
||
@jax.jit | ||
def locked_centroidal_spatial_inertia( | ||
model: js.model.JaxSimModel, data: js.data.JaxSimModelData | ||
): | ||
""" | ||
Compute the locked centroidal spatial inertia of the model. | ||
Args: | ||
model: The model to consider. | ||
data: The data of the considered model. | ||
Returns: | ||
The locked centroidal spatial inertia of the model. | ||
""" | ||
|
||
with data.switch_velocity_representation(VelRepr.Body): | ||
B_Mbb_B = js.model.locked_spatial_inertia(model=model, data=data) | ||
|
||
W_H_B = data.base_transform() | ||
W_p_CoM = com_position(model=model, data=data) | ||
|
||
match data.velocity_representation: | ||
case VelRepr.Inertial | VelRepr.Mixed: | ||
W_H_G = W_H_GW = jnp.eye(4).at[0:3, 3].set(W_p_CoM) | ||
case VelRepr.Body: | ||
W_H_G = W_H_GB = W_H_B.at[0:3, 3].set(W_p_CoM) | ||
case _: | ||
raise ValueError(data.velocity_representation) | ||
|
||
B_H_G = jaxlie.SE3.from_matrix(jaxsim.math.Transform.inverse(W_H_B) @ W_H_G) | ||
|
||
B_Xv_G = B_H_G.adjoint() | ||
G_Xf_B = B_Xv_G.transpose() | ||
|
||
return G_Xf_B @ B_Mbb_B @ B_Xv_G | ||
|
||
|
||
@jax.jit | ||
def average_centroidal_velocity( | ||
model: js.model.JaxSimModel, data: js.data.JaxSimModelData | ||
) -> jtp.Vector: | ||
r""" | ||
Compute the average centroidal velocity of the model. | ||
Args: | ||
model: The model to consider. | ||
data: The data of the considered model. | ||
Returns: | ||
The average centroidal velocity of the model. | ||
Note: | ||
The average velocity is expressed in the mixed frame | ||
:math:`G = ({}^W \mathbf{p}_{\text{CoM}}, [C])`, where :math:`[C] = [W]` if the | ||
active velocity representation is either inertial-fixed or mixed, | ||
and :math:`[C] = [B]` if the active velocity representation is body-fixed. | ||
""" | ||
|
||
ν = data.generalized_velocity() | ||
G_J = average_centroidal_velocity_jacobian(model=model, data=data) | ||
|
||
return G_J @ ν | ||
|
||
|
||
@jax.jit | ||
def average_centroidal_velocity_jacobian( | ||
model: js.model.JaxSimModel, data: js.data.JaxSimModelData | ||
) -> jtp.Matrix: | ||
r""" | ||
Compute the Jacobian of the average centroidal velocity of the model. | ||
Args: | ||
model: The model to consider. | ||
data: The data of the considered model. | ||
Returns: | ||
The Jacobian of the average centroidal velocity of the model. | ||
Note: | ||
The frame corresponding to the output representation of this Jacobian is either | ||
:math:`G[W]`, if the active velocity representation is inertial-fixed or mixed, | ||
or :math:`G[B]`, if the active velocity representation is body-fixed. | ||
""" | ||
|
||
G_J = centroidal_momentum_jacobian(model=model, data=data) | ||
G_Mbb = locked_centroidal_spatial_inertia(model=model, data=data) | ||
|
||
return jnp.linalg.inv(G_Mbb) @ G_J |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Probably a good idea for a future release might be to use
pixi
for the CI, so we don't need to install the whole gazebo package from aptThere was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
While we nowadays use widely conda-forge, I still think that most people (especially those that want to give JaxSim a quick try) will use PyPI in a virtualenv. I'd agree to add a
pixi
orconda
test in parallel.