Skip to content

Add Vizard visualization support for MuJoCo multi-body scenes#1287

Draft
ReeceHumphreys wants to merge 4 commits intodevelopfrom
feature/mujoco-vizard
Draft

Add Vizard visualization support for MuJoCo multi-body scenes#1287
ReeceHumphreys wants to merge 4 commits intodevelopfrom
feature/mujoco-vizard

Conversation

@ReeceHumphreys
Copy link
Contributor

Description

TODO

Verification

TODO

Documentation

TODO

Future work

TODO

@ReeceHumphreys ReeceHumphreys self-assigned this Feb 24, 2026
@ReeceHumphreys ReeceHumphreys added the enhancement New feature or request label Feb 24, 2026
@ReeceHumphreys
Copy link
Contributor Author

@juan-g-bonilla definitely want your feedback on this as the resident MuJoCo guy. Want to make sure not doing anything dumb here haha.

Comment on lines +33 to +40
struct MJGeomInfo {
std::string bodyName;
int type;
std::vector<double> size;
std::vector<double> pos;
std::vector<double> quat;
std::vector<double> rgba;
};
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is interesting, you shouldn't have to define this here since it's already in MJScene.h. Duplicating the definition might lead to divergence.

Comment on lines +45 to +48
std::vector<double> size; ///< Size parameters (3 elements).
std::vector<double> pos; ///< Position in body frame (3 elements).
std::vector<double> quat; ///< Quaternion in body frame (4 elements: w, x, y, z).
std::vector<double> rgba; ///< Color (4 elements, 0-1 range).
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Any chance to make these std::array? They are fixed-size after all.

Comment on lines +45 to +48
std::vector<double> size; ///< Size parameters (3 elements).
std::vector<double> pos; ///< Position in body frame (3 elements).
std::vector<double> quat; ///< Quaternion in body frame (4 elements: w, x, y, z).
std::vector<double> rgba; ///< Color (4 elements, 0-1 range).
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If not changed to std::array, consider initializing to their correct size:

std::vector<double> size(3);

Comment on lines +243 to +250
info.size = {m->geom_size[i * 3], m->geom_size[i * 3 + 1], m->geom_size[i * 3 + 2]};
info.pos = {m->geom_pos[i * 3], m->geom_pos[i * 3 + 1], m->geom_pos[i * 3 + 2]};
info.quat = {m->geom_quat[i * 4], m->geom_quat[i * 4 + 1],
m->geom_quat[i * 4 + 2], m->geom_quat[i * 4 + 3]};
info.rgba = {static_cast<double>(m->geom_rgba[i * 4]),
static_cast<double>(m->geom_rgba[i * 4 + 1]),
static_cast<double>(m->geom_rgba[i * 4 + 2]),
static_cast<double>(m->geom_rgba[i * 4 + 3])};
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is just preference, but I prefer algorithm-oriented style to these operations:

std::copy_n(m->geom_size + i * 3, 3, std::begin(info.size));

if you use std::array,

or:

std::copy_n(m->geom_size + i * 3, 3, std::back_inserter(info.size));

if you use std::vector.

Most of mujoco code is written with algorithms.

And:

std::transform(m->geom_rgba + i * 4, m->geom_size + (i+1) * 4, std::begin(info.rgba),
               [](float v) { return static_cast<double>(v); });

static_cast<double>(m->geom_rgba[i * 4 + 2]),
static_cast<double>(m->geom_rgba[i * 4 + 3])};

geoms.push_back(std::move(info));
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

nice std::move

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you want, you could do in the beginning of the loop:

    for (int i = 0; i < m->ngeom; i++) {
        int bodyId = m->geom_bodyid[i];
        if (bodyId == 0) continue;

        auto& info = geoms.emplace_back();

and eliminate the push back at the end (plus a spurious allocation of MJGeomInfo at the start of the loop for the case bodyId == 0.

*/
struct MJGeomInfo {
std::string bodyName; ///< Name of the body this geom belongs to.
int type; ///< MuJoCo geom type (e.g. mjGEOM_BOX=6, mjGEOM_SPHERE=2, mjGEOM_CYLINDER=5, etc.).
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Probably good to initialize to int type = -1. Don't like garbage by default.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually mjGEOM_NONE would be the more consistent initial value here to follow the mujoco convention.

Comment on lines +1 to +3
HYPSO 1
1 51053U 22002BX 25279.47924866 .00028852 00000-0 56053-3 0 9998
2 51053 97.3197 349.0390 0004257 136.0807 224.0782 15.47578936207406
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

sorry to be like this, but these files should probably be added on their own commit since they're not related to "Add body and geom introspection API to MJScene and MJSpec"

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually, this files might not be related to the PR at all haha

# Position offset in body frame
offset = list(geom.pos)

# Convert quaternion (w, x, y, z) to 3-2-1 Euler angles (z, y, x)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Consider using EP2Euler321 from RigidBodyKinematics.py (but double check that function is doing what you expect!).

Comment on lines +620 to +621
rgba = list(geom.rgba)
color = [int(c * 255) for c in rgba]
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can you do?:

color = [int(c * 255) for c in geom.rgba]

Comment on lines +1407 to +1408
# Walk up the MuJoCo body tree to find the nearest ancestor that
# is in bodyNames
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't believe that's what's going on?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok upon further inspection that is what's going on but simply because bodyNames retrieves all bodies, so find the nearest ancestor that is in bodyNames just means get parent body. I think the comment is more confusing than helpful.

Comment on lines +1384 to +1385
if sc.getBody(name).isFree():
hubName = name
Copy link
Contributor

@juan-g-bonilla juan-g-bonilla Feb 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

MuJoCo scenes support multiple top-level spacecraft. The intended pattern is to support multiple spacecraft by having multiple free bodies in the same scene, not multiple scenes. It'd be great to support that.

# Walk up the MuJoCo body tree to find the nearest ancestor that
# is in bodyNames
parentName = sc.getBodyParentName(name)
scData.parentSpacecraftName = parentName if parentName else hubName
Copy link
Contributor

@juan-g-bonilla juan-g-bonilla Feb 24, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You can do:

scData.parentSpacecraftName = sc.getBodyParentName(name) or hubName

matter of taste I guess.

# Add the hub body first as the top-level spacecraft
scData = vizInterface.VizSpacecraftData()
scData.spacecraftName = hubName
spacecraftParentName = hubName
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you actually never get to use spacecraftParentName since you continue out of this loop.

_createCustomModelsFromMJScene(scSim.vizMessenger, sc)

c += 1
continue
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you're feeling up for a bigger refactor (you can just ask Claude or Codex to help you), I would try to split enableUnityVisualization from this kilometric function into several functions:

    for sc in scList:
        # Check if this is an MJScene object
        if mujocoFound and isinstance(sc, mujoco.MJScene):
            _handleMJScene(...)
        else:
            if isinstance(sc, spacecraft.Spacecraft):
                _handleSpacecraft(...)
            else:
                _handleEffector(...)
            _handleSubEffectors()

(not necessarily like that, but you get the idea)

Copy link
Contributor

@juan-g-bonilla juan-g-bonilla left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I have been summoned! Great PR. I left a lot of comments because reviewing PRs is my happy place, but it's mostly about how I would write some code rather than any "mistakes". Feel free to accept, ignore, or argue about any of my comments (I love an argument).

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

enhancement New feature or request

Projects

Status: No status

Development

Successfully merging this pull request may close these issues.

Support MuJoCo message passthrough to Vizard

2 participants