Tutorial 203: Ball race in MuJoCo
This tutorial demonstrates coordsys_mujoco, which starts a MuJoCo simulation
and tracks the location of multiple objects with Ninbot’s POS library.
The example runs a physics simulation of 20 coloured balls rolling down a slope through a field of obstacles and into a funnel, and uses POS coordinate systems to detect and rank the first three balls to reach the end of the course at the bottom.
Overview
coordsys_mujoco wraps any MuJoCo body, geometry, site, or camera as a live
POS position coordinate system.
Its offset is read from mjData on every transformation query, so it stays in sync with
the simulation at all times.
The POS library itself has no dependency on MuJoCo.
There is some C++ concepts magic in place to compile for MuJoCo only when the user’s program
so requires it.
Only code that actually instantiates coordsys_mujoco — such as this tutorial — needs
to link against libmujoco, but not the POS library by itself.
Once MuJoCo coordinate systems are initialized, they are integrated seamlessly into the POS coordinate tree and can be used like any other coordinate system.
The Scene
The simulation scene (ball_scene.xml) consists of:
-
A course track: A 10-degree slope, 8 m long and 1.4 m wide, with side barriers and a back wall.
-
20 free-falling coloured balls released in a compact cluster at the top.
-
A zigzag field of thin cylindrical pegs that deflect the balls as they roll down.
-
Small cubic wedges along the barriers that redirect balls running along the edges back toward the centre.
-
A funnel at the bottom that channels balls into the goal collecting them by order of arrival.
-
A MuJoCo site named
goalat the funnel exit, whose +X axis points into the goal.
When the simulation starts, the balls fall on the slope and roll their way down to the goal, where they are collected in a funnel-like structure.
The Code
#include <mujoco/mujoco.h>
#include <algorithm>
#include <print>
#include <string>
import ninbot;
std::array<std::string_view, 20> ball_colours = {
"red", "green", "blue", "yellow", "cyan", "magenta",
"darkred", "darkgreen", "darkblue", "darkyellow", "darkcyan", "darkmagenta",
"pink", "white", "grey", "black", "darkgrey", "sea", "brown", "lemon"
};
bool end_of_race( std::vector<nin::coordsys_mujoco> & balls,
nin::coordsys_mujoco const& goal )
{
int goal_count = 0;
for (nin::coordsys_mujoco const& ball : balls)
if (ball.origin().map_to(goal).x.SI() > 0)
goal_count++;
auto compare_positions = [&](auto const& a, auto const& b)
{
return a.origin().map_to(goal).x > b.origin().map_to(goal).x;
};
if (goal_count >= 4) {
std::ranges::partial_sort(balls, balls.begin() + 3, compare_positions);
return true;
}
return false;
}
int main()
{
std::string_view model_path = "ball_scene.xml";
mjModel* model = mj_loadXML(model_path.data(), nullptr, nullptr, 0);
if (!model)
throw std::runtime_error("Failed to load model.");
mjData* data = mj_makeData(model);
std::vector<nin::coordsys_mujoco> balls;
for (std::string_view colour : ball_colours)
balls.emplace_back(model, data, mjOBJ_BODY, colour.data());
nin::coordsys_mujoco goal(model, data, mjOBJ_SITE, "goal");
while (true) {
mj_step(model, data);
if (end_of_race(balls, goal)) {
std::println("The race is over! And the winner is...");
std::println("1st 🥇 {} — Congratulations, champion!", balls[0]->name);
std::println("2nd 🥈 {} — Well done!", balls[1]->name);
std::println("3rd 🥉 {} — Great race!", balls[2]->name);
break;
}
}
mj_deleteData(data);
mj_deleteModel(model);
}
Output
The race is over! And the winner is...
1st 🥇 lemon — Congratulations, champion!
2nd 🥈 pink — Well done!
3rd 🥉 brown — Great race!
Building the Code
Save the example as ball_race.c++ alongside this CMakeLists.txt:
cmake_minimum_required(VERSION 4.0)
project(ball-race LANGUAGES CXX)
find_package(Ninbot REQUIRED)
find_package(MuJoCo REQUIRED)
add_executable(ball-race ball_race.c++)
target_link_libraries(ball-race PRIVATE ninbot::ninbot mujoco::mujoco)
configure_file(
${CMAKE_CURRENT_SOURCE_DIR}/../../assets/tutorial-203-ball-race/ball_scene.xml
${CMAKE_CURRENT_BINARY_DIR}/ball_scene.xml
COPYONLY
)
Configure and build, pointing CMake at the MuJoCo installation and the ninbot build tree:
cmake -B build -G Ninja \
-DCMAKE_PREFIX_PATH=/path/to/ninbot/build \
-DCMAKE_MODULE_PATH=/path/to/ninbot/cmake \
-DMUJOCO_ROOT=/path/to/mujoco
cmake --build build
./build/ball-race
Walkthrough
end_of_race: detecting and ranking the podium
end_of_race encapsulates all of the POS logic: it counts how many balls have
crossed the goal, and once at least four have arrived, it ranks them in place and
returns true.
It is a free function rather than inline code in main to keep the POS
queries self-contained and readable in isolation, without being buried in the
simulation loop.
The function first counts how many balls have crossed the goal by mapping each ball’s origin into the goal coordinate system and reading its x component:
if (ball.origin().map_to(goal).x.SI() > 0)
goal_count++;
ball.origin() returns a coord_value representing the ball’s origin expressed in
its own coordinate system.
map_to(goal) transforms that value into the goal coordinate system and returns
a position_qty.
When the result’s x component is positive, the ball is on the far side of the goal
site — inside the goal.
Once at least four balls have arrived, the same pattern drives the comparator
passed to std::ranges::partial_sort to rank balls by how far into the goal they
have travelled:
return a.origin().map_to(goal).x > b.origin().map_to(goal).x;
This avoids having to carry the colour strings alongside the coordinate systems in the application logic.
Loading the model and creating coordinate systems
First, load the MuJoCo model and simulation data as usual:
mjModel* model = mj_loadXML(model_path.data(), nullptr, nullptr, 0);
mjData* data = mj_makeData(model);
Then wrap the MuJoCo objects as POS coordinate systems:
std::vector<nin::coordsys_mujoco> balls;
for (std::string_view colour : ball_colours)
balls.emplace_back(model, data, mjOBJ_BODY, colour.data());
nin::coordsys_mujoco goal(model, data, mjOBJ_SITE, "goal");
Each coordsys_mujoco is constructed with the model, the data, the MuJoCo object type,
and the name of the object.
The constructor looks up the named object in the model once and records its integer ID.
From that point on the coordinate system behaves like any other POS coordsys —
except that every transformation query re-reads the object’s current pose from data.
Because all coordinate systems share the same data pointer, a single mj_step call
advances all of them simultaneously with no extra bookkeeping.
Advancing the simulation
coordsys_mujoco holds a raw pointer to mjData.
Calling mj_step writes new poses into that data structure, so all existing
coordsys_mujoco instances reflect the new state immediately on the next query —
no re-construction or explicit update is needed:
mj_step(model, data); // all coordsys_mujoco objects now reflect the new state