Skip to content

Commit

Permalink
Skip deprecated mju_rotVecMat and mju_rotVecMatT in Python bindings.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 647275284
Change-Id: I371236182b22eb399041959901085bb82af3f670
  • Loading branch information
yuvaltassa authored and Copybara-Service committed Jun 27, 2024
1 parent 13fce3e commit 62e2842
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 26 deletions.
27 changes: 15 additions & 12 deletions doc/changelog.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,17 @@ General

1. Removed deprecated ``mj_makeEmptyFileVFS`` and ``mj_findFileVFS`` functions.

**Migration:** Use ``mj_addBufferVFS`` to copy a buffer into a VFS file directly.
**Migration:** Use:ref:`mj_addBufferVFS` to copy a buffer into a VFS file directly.

2. Calls to ``mj_defaultVFS`` may allocate memory inside VFS, and the corresponding
``mj_deleteVFS`` must be called to deallocate any internal allocated memory.
2. Calls to:ref:`mj_defaultVFS` may allocate memory inside VFS, and the corresponding
:ref:`mj_deleteVFS` must be called to deallocate any internal allocated memory.

3. Added a new API for :doc:`procedural model manipulation<programming/modeledit>`. Fixes :github:issue:`364`.
3. Deprecated :ref:`mju_rotVecMat` and :ref:`mju_rotVecMatT` in favor of :ref:`mju_mulMatVec3` and
:ref:`mju_mulMatTVec3`. These function names and argument order are more consistent with the rest of the API.
The older functions have been removed from the Python bindings and will be removed from the C API in the next
release.

4. Added a new API for :doc:`procedural model manipulation<programming/modeledit>`. Fixes :github:issue:`364`.
Still missing:

- Detailed documentation.
Expand All @@ -27,14 +32,12 @@ General
:align: right
:width: 240px

4. Added support for orthographic cameras. This is available for both fixed cameras and the free camera, using the
5. Added support for orthographic cameras. This is available for both fixed cameras and the free camera, using the
:ref:`camera/orthographic<body-camera-orthographic>` and :ref:`global/orthographic<visual-global-orthographic>`
attributes, respectively.
5. Added :ref:`maxhullvert<asset-mesh-maxhullvert>`, the maximum number of vertices in a mesh's convex hull.
6. Added :ref:`mj_setKeyframe` for saving the current state into a model keyframe.
7. Added support for ``ball`` joints in the URDF parser ("spherical" in URDF).
8. Deprecated :ref:`mju_rotVecMat` and :ref:`mju_rotVecMatT` in favor of :ref:`mju_mulMatVec3` and
:ref:`mju_mulMatTVec3`. These functions names and argument ordering are more consistent with the rest of the API.
6. Added :ref:`maxhullvert<asset-mesh-maxhullvert>`, the maximum number of vertices in a mesh's convex hull.
7. Added :ref:`mj_setKeyframe` for saving the current state into a model keyframe.
8. Added support for ``ball`` joints in the URDF parser ("spherical" in URDF).
9. Replaced ``mjUSEDOUBLE`` which was previously hard-coded in
`mjtnum.h <https://github.com/google-deepmind/mujoco/blob/main/include/mujoco/mjtnum.h>`__
with the build-time flag ``mjUSESINGLE``. If this symbol is not defined, MuJoCo will use double-precision floating
Expand Down Expand Up @@ -231,10 +234,10 @@ General
:at:`ctrlrange` or :at:`actrange` (respectively), according to the range of the transmission
target (joint or tendon). See :ref:`position/inheritrange<actuator-position-inheritrange>` for
details.
2. Deprecated :ref:`mj_makeEmptyFileVFS` in favor of :ref:`mj_addBufferVFS`. :ref:`mjVFS` now computes checksums of
2. Deprecated ``mj_makeEmptyFileVFS`` in favor of :ref:`mj_addBufferVFS`. :ref:`mjVFS` now computes checksums of
its internal file buffers. :ref:`mj_addBufferVFS` allocates an empty buffer with a given name in an mjVFS and
copies the data buffer into it, combining and replacing the deprecated two-step process of calling
:ref:`mj_makeEmptyFileVFS` followed by a direct copy into the given mjVFS internal file buffer.
``mj_makeEmptyFileVFS`` followed by a direct copy into the given mjVFS internal file buffer.
3. Added :ref:`mj_angmomMat` which computes the ``3 x nv`` angular momentum matrix :math:`H(q)`, providing the linear
mapping from generalized velocities to subtree angular momentum :math:`h = H \dot q`. Contribution by
:github:user:`v-r-a`.
Expand Down
16 changes: 8 additions & 8 deletions python/mujoco/functions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#include <array>
#include <cstdint>
#include <memory>
#include <sstream>
#include <string>
#include <optional>

Expand All @@ -29,6 +28,7 @@
#include "functions.h"
#include "private.h"
#include "raw.h"
#include "structs.h"
#include <pybind11/eigen.h>
#include <pybind11/pybind11.h>
#include <pybind11/stl.h>
Expand Down Expand Up @@ -108,9 +108,10 @@ PYBIND11_MODULE(_functions, pymodule) {
// Skipped: mj_copyModel (have MjModel.__copy__, memory managed by MjModel)
pymodule.def(
"mj_saveModel",
[](const MjModelWrapper& m, const std::optional<std::string>& filename = std::nullopt,
std::optional<
Eigen::Ref<Eigen::Vector<std::uint8_t, Eigen::Dynamic>>> buffer = std::nullopt) {
[](const MjModelWrapper& m,
const std::optional<std::string>& filename = std::nullopt,
std::optional<Eigen::Ref<Eigen::Vector<std::uint8_t, Eigen::Dynamic>>>
buffer = std::nullopt) {
void* buffer_ptr = nullptr;
int buffer_sz = 0;
if (buffer.has_value()) {
Expand All @@ -122,8 +123,7 @@ PYBIND11_MODULE(_functions, pymodule) {
buffer_ptr, buffer_sz);
},
py::arg("m"), py::arg_v("filename", std::nullopt),
py::arg_v("buffer", std::nullopt),
py::doc(traits::mj_saveModel::doc),
py::arg_v("buffer", std::nullopt), py::doc(traits::mj_saveModel::doc),
py::call_guard<py::gil_scoped_release>());
// Skipped: mj_loadModel (have MjModel.from_binary_path)
// Skipped: mj_deleteModel (have MjModel.__del__)
Expand Down Expand Up @@ -700,8 +700,8 @@ PYBIND11_MODULE(_functions, pymodule) {
Def<traits::mju_dist3>(pymodule);
Def<traits::mju_mulMatVec3>(pymodule);
Def<traits::mju_mulMatTVec3>(pymodule);
Def<traits::mju_rotVecMat>(pymodule);
Def<traits::mju_rotVecMatT>(pymodule);
// skipped: mju_rotVecMat
// skipped: mju_rotVecMatT
Def<traits::mju_cross>(pymodule);
Def<traits::mju_zero4>(pymodule);
Def<traits::mju_unit4>(pymodule);
Expand Down
12 changes: 6 additions & 6 deletions src/engine/engine_collision_box.c
Original file line number Diff line number Diff line change
Expand Up @@ -806,8 +806,8 @@ int mjc_BoxBox(const mjModel* M, const mjData* D, mjContact* con, int g1, int g2
if (q2) {
mju_mulMatMatT3(r, rotmore, rot);

// mju_rotVecMat(p,pos12,rotmore);
// mju_rotVecMat(tmp1,size2,rotmore);
// mju_mulMatVec3(p,rotmore,pos12);
// mju_mulMatVec3(tmp1,rotmore,size2);

rotaxis(p, pos12);
rotaxis(tmp1, size2);
Expand All @@ -818,8 +818,8 @@ int mjc_BoxBox(const mjModel* M, const mjData* D, mjContact* con, int g1, int g2

rotmatx(r, rot);

// mju_rotVecMat(p,pos21,rotmore);
// mju_rotVecMat(tmp1,size1,rotmore);
// mju_mulMatVec3(p,rotmore,pos21);
// mju_mulMatVec3(tmp1,rotmore,size1);

rotaxis(p, pos21);
rotaxis(tmp1, size1);
Expand Down Expand Up @@ -1074,8 +1074,8 @@ int mjc_BoxBox(const mjModel* M, const mjData* D, mjContact* con, int g1, int g2
f2 = -1;
}

// mju_rotVecMat(p,pos21,rotmore);
// mju_rotVecMat(rnorm,clnorm,rotmore);
// mju_mulMatVec3(p,rotmore,pos21);
// mju_mulMatVec3(rnorm,rotmore,clnorm);
rotaxis(p, pos21);
rotaxis(rnorm, clnorm);

Expand Down

0 comments on commit 62e2842

Please sign in to comment.