You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I am a phd student at mit using mujoco for my research on C.elegans neuromechanics
My setup
mujoco/mjx 3.4.0, python, linux ubuntu.
My question
I followed the mjSpec.ipynb example for scaling a mujoco model to downscale my model but for the behavior of each model diverges. It seems like the actuator strength on the scaled model is much higher relative to the mass than it is in the unscaled version even though I am scaling the actuator gain as mentioned in the notebook. Here is a video of the unscaled vs scaled model with random noise injection:
Are there other parameters I should be scaling such as the joint armature?
Minimal model and/or code that explain my question
If you encountered the issue in a complex model, please simplify it as much as possible (while still reproducing the issue).
Model:
I've taken the C. elegans biomechanical model from this repo. It's based on the n -link swimmer from gymnasium and contains 25 body components with corresponding meshes. The total length of the model is 1mm. I am trying to simulate a worm on agar so I'm using air as the medium. It is constrained to 2D movement in the xy plane with 24 joints hinge joints actuated by 95 muscles. Each joint is actuated by a set of 4 muscles organized into dorsal/ventral and left/right. Except for the last one which is missing its ventral left muscle. In order to get the model to work efficiently with mjx I removed mesh contact computation and used collision geoms instead. I also only kept contacts between the floor and the body (ie no inter body contact).
I've attached a zip file containing the arena and body model I'm using to create the scene via mjSpec. I've also posted the unscaled vs scaled models generated by mjSpec as well as the code used to generate these specs.
Code:
Here is my scaling code to make it easier to see in case theres something obvious that pops out:
defdm_scale_spec(spec, scale):
scaled_spec=spec.copy()
# Traverse the kinematic tree, scaling all geomsdefscale_bodies(parent, scale=1.0):
body=parent.first_body()
whilebody:
ifbody.posisnotNone:
body.pos=body.pos*scaleforgeominbody.geoms:
geom.fromto=geom.fromto*scalegeom.size=geom.size*scaleifgeom.posisnotNone:
geom.pos=geom.pos*scaleforsiteinbody.sites:
ifsite.posisnotNone:
site.pos=site.pos*scaleifsite.sizeisnotNone:
site.size=site.size*scaleforjointinbody.joints:
ifjoint.posisnotNone:
joint.pos=joint.pos*scalescale_bodies(body, scale)
body=parent.next_body(body)
# if scale_actuators:# # scale gearformeshinscaled_spec.meshes:
mesh.scale=mesh.scale*scaleforactuatorinscaled_spec.actuators:
# scale the actuator gear by (scale ** 2),# this is because muscle force-generating capacity# scales with the cross-sectional area of the muscleactuator.gear=actuator.gear*scale*scale# scale the z-position for all keypointsforkeypointinscaled_spec.keys:
qpos=keypoint.qposqpos[2] =qpos[2] *scalekeypoint.qpos=qposkeypoint.qpos[2] =keypoint.qpos[2] *scalescale_bodies(scaled_spec.worldbody, scale)
returnscaled_spec
reacted with thumbs up emoji reacted with thumbs down emoji reacted with laugh emoji reacted with hooray emoji reacted with confused emoji reacted with heart emoji reacted with rocket emoji reacted with eyes emoji
Uh oh!
There was an error while loading. Please reload this page.
Uh oh!
There was an error while loading. Please reload this page.
-
Intro
Hi!
I am a phd student at mit using mujoco for my research on C.elegans neuromechanics
My setup
mujoco/mjx 3.4.0, python, linux ubuntu.
My question
I followed the mjSpec.ipynb example for scaling a mujoco model to downscale my model but for the behavior of each model diverges. It seems like the actuator strength on the scaled model is much higher relative to the mass than it is in the unscaled version even though I am scaling the actuator gain as mentioned in the notebook. Here is a video of the unscaled vs scaled model with random noise injection:
Screencast.from.2026-01-16.12-42-53.webm
Screencast.from.2026-01-16.12-43-55.webm
Are there other parameters I should be scaling such as the joint armature?
Minimal model and/or code that explain my question
If you encountered the issue in a complex model, please simplify it as much as possible (while still reproducing the issue).
Model:
I've taken the C. elegans biomechanical model from this repo. It's based on the n -link swimmer from gymnasium and contains 25 body components with corresponding meshes. The total length of the model is 1mm. I am trying to simulate a worm on agar so I'm using air as the medium. It is constrained to 2D movement in the xy plane with 24 joints hinge joints actuated by 95 muscles. Each joint is actuated by a set of 4 muscles organized into dorsal/ventral and left/right. Except for the last one which is missing its ventral left muscle. In order to get the model to work efficiently with mjx I removed mesh contact computation and used collision geoms instead. I also only kept contacts between the floor and the body (ie no inter body contact).
I've attached a zip file containing the arena and body model I'm using to create the scene via mjSpec. I've also posted the unscaled vs scaled models generated by mjSpec as well as the code used to generate these specs.
model_scaling.zip
Code:
Here is my scaling code to make it easier to see in case theres something obvious that pops out:
Confirmations
Beta Was this translation helpful? Give feedback.
All reactions