Skip to content

Conversation

@Juliaj
Copy link
Contributor

@Juliaj Juliaj commented Jan 15, 2026

@saikishor
Copy link
Member

saikishor commented Jan 15, 2026

@Juliaj Thank you for the PR. This is very interesting. The build is failing due to the different API i guess, please verify

@Juliaj
Copy link
Contributor Author

Juliaj commented Jan 15, 2026

Thanks, @saikishor,

I see more changes in this PR than the contact sensor integration itself.

The additional fix is for unit tests due to #70

@Juliaj Juliaj force-pushed the contact_sensor_support branch from bee46a0 to 68ae0be Compare January 15, 2026 08:32
Copy link
Collaborator

@eholum-nasa eholum-nasa left a comment

Choose a reason for hiding this comment

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

Thanks @Juliaj!

I am not particularly familiar with contact sensors, is it normal for them to only be between two specific bodies? If we only wanted to know when something was in contact with anything (say, a foot to the floor or hand to something) we might want to use touch sensors? It might be a more mujoco way of checking raw contact for a given site. It could probably simplify the registration and read functions, like users could set some kind of force threshold for contact? I think the debouncing logic would be similar.

Maybe a slightly different use case but this seems very specific to me?

@Juliaj
Copy link
Contributor Author

Juliaj commented Jan 15, 2026

Hi @eholum-nasa, this is a new subject area for me as well, so thank you very much for the thoughtful questions.

Based on some of my reading, contact modeling is generally a hard problem. As for MuJoCo, you're right: there isn't a "contact sensor". The intent of this PR is to add contact detection by scanning MuJoCo’s generated contacts (mjData->contact) and to add a bridge between the MuJoCo Contact API (usage here) and a ros2_control state interface for inference with an ONNX model.

If we only wanted to know when something was in contact with anything (say, a foot to the floor or hand to something) we might want to use touch sensors?

Touch sensors are a good fit when the requirement is “is this site touching anything?”, but they are not inherently pair-specific and won’t tell you what was contacted. Pair-specific semantics (“foot vs world”) may matter in biped gait control because decisions depend on what the foot is contacting, not just that it is contacting something.

I also have a debug use case: I need to verify that contact is detected at the bottom of the Open Duck Mini’s feet (i.e., left_foot_bottom_tpu, right_foot_bottom_tpu) to investigate the degradation of the ONNX policy in a MuJoCo ROS 2 control simulation. With the same policy and command, Duck Mini walks forward in MuJoCo simulation. When wrapping it in a custom ros2_controller, with the same command, the robot doesn’t walk forward and instead shuffles its legs in place. Pair-specific contact detection provides a lot of insight here.

contact sensors, is it normal for them to only be between two specific bodies?

That said, even with this support in mujoco_ros2_control, the sim-to-real gap exists because there typically isn’t a universal “contact signal” available on the real robot: contact sensing is hardware-specific.

Maybe a slightly different use case but this seems very specific to me?

Good question, I did a bit more searching for other biped use cases. Berkeley uses this for their Humanoid-Lite.
However, in their case, the contact info is not part of the observation; instead, it is used for reward calculation via ContactSensorCfg provided by Isaac Gym / IsaacLab (PhysX). It's derived by thresholding the per-foot net contact force (e.g., (f_z > \tau)) and optionally tracking air-time.

From a contact-API exposure perspective, I'd say this helps with data gathering if we want to train a model in a MuJoCo ROS 2 control simulation in addition to inferece use case.

Where should we take this?

  1. Go with your suggestion of using the touch sensor option. Users can add <touch site="..."> sensors in the MJCF (e.g., on foot sites). We can then read the resulting signal from sensordata, optionally applying a threshold and the same debounce/hysteresis logic. This is probably workable for my inference use case. But for collisions/obstacles, this may not be sufficient because touch sensors don't tell you what was contacted.

  2. Morph this into an exercise in exposing the MuJoCo Contact API for training/inference needs in ros2_control simulation, e.g. defining param to specify contact pairs and state interface name etc.

  3. Close this, go back to an artificial gait-phase function, which I originally created in my custom Motion Controller. I put it aside after finding out we may be able to get this directly by scanning the contact list (mjData->contact) with debounce/hysteresis for gait.

What do you think?

@saikishor, at Pal Robotics, do you guys need to solve similar problem ?

@saikishor
Copy link
Member

@Juliaj we usually deal with the force torque sensors at the ankles and use them logically. We also have a contact estimator to estimate the contacts

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

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants