Skip to content

Commit 37d7591

Browse files
Google DeepMindcopybara-github
authored andcommitted
Add support for user-defined figures in the MuJoCo viewer.
PiperOrigin-RevId: 726983516 Change-Id: Ifb821f3cafb163d4f3077d76b0668037b4bc5a9c
1 parent 6f0bd0a commit 37d7591

File tree

5 files changed

+73
-20
lines changed

5 files changed

+73
-20
lines changed

doc/changelog.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@ Feature promotion
2525

2626
General
2727
^^^^^^^
28+
- Add support for custom plots in the MuJoCo viewer by exposing a ``viewport`` property, a ``set_figures`` method,
29+
and a ``clear_figures`` method.
2830
- Separate collision and deformation meshes for :ref:`flex<deformable-flex>`. This enables a fixed cost for the soft
2931
body computations, while preserving the fidelity of high-resolution collisions.
3032
- Added :ref:`mjs_setDeepCopy` API function. When the deep copy flag is 0, attaching a model will not copy it to the

python/mujoco/simulate.cc

Lines changed: 44 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
#include <pybind11/gil.h>
2929
#include <pybind11/pybind11.h>
3030
#include <pybind11/pytypes.h>
31+
#include <pybind11/stl.h>
3132

3233
namespace mujoco::python {
3334
namespace {
@@ -69,11 +70,10 @@ class UIAdapterWithPyCallback : public Adapter {
6970
class SimulateWrapper {
7071
public:
7172
SimulateWrapper(std::unique_ptr<PlatformUIAdapter> platform_ui_adapter,
72-
py::object cam, py::object opt,
73-
py::object pert, py::object user_scn, bool is_passive)
73+
py::object cam, py::object opt, py::object pert,
74+
py::object user_scn, bool is_passive)
7475
: simulate_(new mujoco::Simulate(
75-
std::move(platform_ui_adapter),
76-
cam.cast<MjvCameraWrapper&>().get(),
76+
std::move(platform_ui_adapter), cam.cast<MjvCameraWrapper&>().get(),
7777
opt.cast<MjvOptionWrapper&>().get(),
7878
pert.cast<MjvPerturbWrapper&>().get(), is_passive)),
7979
m_(py::none()),
@@ -126,6 +126,28 @@ class SimulateWrapper {
126126
py::object GetModel() const { return m_; }
127127
py::object GetData() const { return d_; }
128128

129+
mjrRect GetViewport() const {
130+
// Return the viewport corresponding to the 3D view, i.e. the viewer window
131+
// without the UI elements.
132+
return simulate_->uistate.rect[3];
133+
}
134+
135+
void SetFigures(
136+
const std::vector<std::pair<mjrRect, py::object>>& viewports_figures) {
137+
// Pairs of [viewport, figure], where viewport corresponds to the location
138+
// of the figure on the viewer window.
139+
std::vector<std::pair<mjrRect, mjvFigure>> user_figures;
140+
for (const auto& [viewport, figure] : viewports_figures) {
141+
mjvFigure casted_figure = *figure.cast<MjvFigureWrapper&>().get();
142+
user_figures.push_back(std::make_pair(viewport, casted_figure));
143+
}
144+
145+
// Set them all at once to prevent figure flickering.
146+
simulate_->user_figures_ = user_figures;
147+
}
148+
149+
void ClearFigures() { simulate_->user_figures_.clear(); }
150+
129151
private:
130152
mujoco::Simulate* simulate_;
131153
std::atomic_int destroyed_ = 0;
@@ -173,14 +195,14 @@ inline auto CallIfNotNull(void (mujoco::Simulate::*func)(Args...)) {
173195
}
174196

175197
template <typename T>
176-
inline auto GetIfNotNull(T mujoco::Simulate::*member) {
198+
inline auto GetIfNotNull(T mujoco::Simulate::* member) {
177199
return [member](SimulateWrapper& wrapper) -> T& {
178200
return SimulateRefOrThrow(wrapper).*member;
179201
};
180202
}
181203

182204
template <typename T, typename... Args>
183-
inline auto SetIfNotNull(T mujoco::Simulate::*member) {
205+
inline auto SetIfNotNull(T mujoco::Simulate::* member) {
184206
return [member](SimulateWrapper& wrapper, const T& value) -> void {
185207
SimulateRefOrThrow(wrapper).*member = value;
186208
};
@@ -205,8 +227,7 @@ PYBIND11_MODULE(_simulate, pymodule) {
205227
py::object key_callback) {
206228
bool is_passive = !run_physics_thread;
207229
return std::make_unique<SimulateWrapper>(
208-
std::make_unique<UIAdapterWithPyCallback<UIAdapter>>(
209-
key_callback),
230+
std::make_unique<UIAdapterWithPyCallback<UIAdapter>>(key_callback),
210231
scn, cam, opt, pert, is_passive);
211232
}))
212233
.def("destroy", &SimulateWrapper::Destroy)
@@ -225,8 +246,12 @@ PYBIND11_MODULE(_simulate, pymodule) {
225246
.def("lock", GetIfNotNull(&mujoco::Simulate::mtx),
226247
py::call_guard<py::gil_scoped_release>(),
227248
py::return_value_policy::reference_internal)
249+
.def("set_figures", &SimulateWrapper::SetFigures,
250+
py::arg("viewports_figures"))
251+
.def("clear_figures", &SimulateWrapper::ClearFigures)
228252
.def_property_readonly("m", &SimulateWrapper::GetModel)
229253
.def_property_readonly("d", &SimulateWrapper::GetData)
254+
.def_property_readonly("viewport", &SimulateWrapper::GetViewport)
230255
.def_property_readonly("ctrl_noise_std",
231256
GetIfNotNull(&mujoco::Simulate::ctrl_noise_std),
232257
py::call_guard<py::gil_scoped_release>())
@@ -260,18 +285,17 @@ PYBIND11_MODULE(_simulate, pymodule) {
260285
return sim.exitrequest.load();
261286
}),
262287
py::call_guard<py::gil_scoped_release>())
263-
.def(
264-
"exit",
265-
[](SimulateWrapper& wrapper) {
266-
mujoco::Simulate* sim = wrapper.simulate();
267-
if (!sim) {
268-
return;
269-
}
270-
271-
int value = 0;
272-
sim->exitrequest.compare_exchange_strong(value, 1);
273-
wrapper.WaitUntilExit();
274-
})
288+
.def("exit",
289+
[](SimulateWrapper& wrapper) {
290+
mujoco::Simulate* sim = wrapper.simulate();
291+
if (!sim) {
292+
return;
293+
}
294+
295+
int value = 0;
296+
sim->exitrequest.compare_exchange_strong(value, 1);
297+
wrapper.WaitUntilExit();
298+
})
275299

276300
.def_property_readonly("uiloadrequest",
277301
CallIfNotNull(+[](mujoco::Simulate& sim) {

python/mujoco/viewer.py

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -108,6 +108,23 @@ def d(self):
108108
return sim.d
109109
return None
110110

111+
@property
112+
def viewport(self):
113+
sim = self._sim()
114+
if sim is not None:
115+
return sim.viewport
116+
return None
117+
118+
def set_figures(self, viewports_figures):
119+
sim = self._sim()
120+
if sim is not None:
121+
sim.set_figures(viewports_figures)
122+
123+
def clear_figures(self):
124+
sim = self._sim()
125+
if sim is not None:
126+
sim.clear_figures()
127+
111128
def close(self):
112129
sim = self._sim()
113130
if sim is not None:

simulate/simulate.cc

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -542,6 +542,10 @@ void ShowSensor(mj::Simulate* sim, mjrRect rect) {
542542
mjr_figure(viewport, &sim->figsensor, &sim->platform_ui->mjr_context());
543543
}
544544

545+
void ShowFigure(mj::Simulate* sim, mjrRect viewport, mjvFigure* fig){
546+
mjr_figure(viewport, fig, &sim->platform_ui->mjr_context());
547+
}
548+
545549
// load state from history buffer
546550
static void LoadScrubState(mj::Simulate* sim) {
547551
// get index into circular buffer
@@ -2588,6 +2592,11 @@ void Simulate::Render() {
25882592
}
25892593
}
25902594

2595+
// user figures
2596+
for (auto& [viewport, figure] : this->user_figures_) {
2597+
ShowFigure(this, viewport, &figure);
2598+
}
2599+
25912600
// finalize
25922601
this->platform_ui->SwapBuffers();
25932602
}

simulate/simulate.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -252,6 +252,7 @@ class Simulate {
252252
// additional user-defined visualization geoms (used in passive mode)
253253
mjvScene* user_scn = nullptr;
254254
mjtByte user_scn_flags_prev_[mjNRNDFLAG];
255+
std::vector<std::pair<mjrRect, mjvFigure>> user_figures_;
255256

256257
// OpenGL rendering and UI
257258
int refresh_rate = 60;

0 commit comments

Comments
 (0)