Create a tracking body and a simulated body #2376
-
IntroHi! I am a master student at UNED, I use MuJoCo for my research on generative human motion. My setupMuJoCo python My questionI’m trying to replicate a publication on human motion generation—specifically ControlVAE, in case anyone needs more references. In this publication, there’s an initial part of the model where a neural network must learn a world model based on a BVH file. It works as follows:
For visualization, I need a character that is not affected by physics, onto which I can apply only the desired rotations. I achieved this by modifying qpos and calling mj_forward. The problem is that I now also need a new character that is subject to physics (i.e., one to which I can apply actions/torques and that responds accordingly). For this second character, I need to call mj_step. I tried calling mj_forward and then mj_step in the loop, assigning zero mass to all the geoms of the “visualization” character so that it wouldn’t be affected by gravity. However, I’m getting the error “body mass is too small, cannot compute center of mass,” which suggests this approach is incorrect. What would be the proper way to do this? Confirmations
|
Beta Was this translation helpful? Give feedback.
Replies: 1 comment 4 replies
-
Hello, mj_step already calls mj_forward, so you do not need to call it separately; just manually set qpos of the visualization kinematic tree. It is also a good idea to set its qvel to 0 as well (otherwise, depending on your integrator it could lead to your character drifting away due to accumulating qvel). Don't forget to disable collisions to visualization character, and I also recommend setting its geoms transparent for clarity. If you do these steps, you can leave the masses as they are for the visu character. In fact, you get the benefit of being able to calculate measure such as CoM, which you can compare with your simulated character. Note that this approach does waste some computation, the engine will try to simulate the visu character, you just overwrite its results every time step. You particularly should take care to only compare kinematics between sim and visu characters, and only after updating the visu state, but before mj_step (otherwise the visu state would be affected). Another approach is using mocap bodies for each separate body segment, and setting their positions and rotations to the global one from the reference animation. Mocap bodies are not updated by the engine hence are cheaper, but there is more book keeping involved when you need to convert back and forth from local and global configurations. Related but not necessary is the gravcomp field for bodies, using which you can disable gravity selectively. However, if you do set the qpos and qvel each frame, it won't be necessary. |
Beta Was this translation helpful? Give feedback.
Hello,
mj_step already calls mj_forward, so you do not need to call it separately; just manually set qpos of the visualization kinematic tree. It is also a good idea to set its qvel to 0 as well (otherwise, depending on your integrator it could lead to your character drifting away due to accumulating qvel). Don't forget to disable collisions to visualization character, and I also recommend setting its geoms transparent for clarity.
If you do these steps, you can leave the masses as they are for the visu character. In fact, you get the benefit of being able to calculate measure such as CoM, which you can compare with your simulated character.
Note that this approach does waste some computa…