Skip to content

Commit

Permalink
Improve inline documentation of mj_passive and mj_subtreeVel.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 579808998
Change-Id: I2cff167c3813964f42a30b06f1adf38b57d62196
  • Loading branch information
yuvaltassa authored and copybara-github committed Nov 6, 2023
1 parent a668788 commit 5a9239e
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
4 changes: 2 additions & 2 deletions doc/APIreference/functions.rst
Original file line number Diff line number Diff line change
Expand Up @@ -803,7 +803,7 @@ mj_passive

.. mujoco-include:: mj_passive

Compute qfrc_passive from spring-dampers, viscosity and density.
Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces.

.. _mj_subtreeVel:

Expand All @@ -812,7 +812,7 @@ mj_subtreeVel

.. mujoco-include:: mj_subtreeVel

subtree linear velocity and angular momentum
Sub-tree linear velocity and angular momentum: compute subtree_linvel, subtree_angmom.

.. _mj_rne:

Expand Down
4 changes: 2 additions & 2 deletions include/mujoco/mujoco.h
Original file line number Diff line number Diff line change
Expand Up @@ -336,10 +336,10 @@ MJAPI void mj_solveM2(const mjModel* m, mjData* d, mjtNum* x, const mjtNum* y, i
// Compute cvel, cdof_dot.
MJAPI void mj_comVel(const mjModel* m, mjData* d);

// Compute qfrc_passive from spring-dampers, viscosity and density.
// Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces.
MJAPI void mj_passive(const mjModel* m, mjData* d);

// subtree linear velocity and angular momentum
// Sub-tree linear velocity and angular momentum: compute subtree_linvel, subtree_angmom.
MJAPI void mj_subtreeVel(const mjModel* m, mjData* d);

// RNE: compute M(qpos)*qacc + C(qpos,qvel); flg_acc=0 removes inertial term.
Expand Down
4 changes: 2 additions & 2 deletions introspect/functions.py
Original file line number Diff line number Diff line change
Expand Up @@ -1666,7 +1666,7 @@
),
),
),
doc='Compute qfrc_passive from spring-dampers, viscosity and density.',
doc='Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces.', # pylint: disable=line-too-long
)),
('mj_subtreeVel',
FunctionDecl(
Expand All @@ -1686,7 +1686,7 @@
),
),
),
doc='subtree linear velocity and angular momentum',
doc='Sub-tree linear velocity and angular momentum: compute subtree_linvel, subtree_angmom.', # pylint: disable=line-too-long
)),
('mj_rne',
FunctionDecl(
Expand Down

0 comments on commit 5a9239e

Please sign in to comment.