google-deepmind / mujoco

Multi-Joint dynamics with Contact. A general purpose physics simulator.
https://mujoco.org
Apache License 2.0
7.8k stars 776 forks source link

Clarification - Coordinate frame of generalized forces, velocities and accelerations of free joints #691

Closed Anderv21 closed 1 year ago

Anderv21 commented 1 year ago

Hi,

I'm a PhD. student and I'm trying to use MuJoCo for the simulation of a real, legged robot. I need to design, test and deploy model-based controllers for such a robot and I have chosen MuJoCo for the testing phase. My application uses MuJoCo in a rather simple manner: sends actuator commands and receives sensor data. I already have a running application that performs the aforementioned functionality.

I want to make sure that the simulated model behaves as close as possible to the actual hardware (same input and output list and same dynamic behavior). Following the documentation, I have been able to reproduce all inputs and outputs of my real system (with the coordinate frames I want for 3D quantities). Furthermore, I believe that all geometric (/kinematic) and inertial parameters are the same as the model I use in my controller. To do a final sanity check I want to compare the Mass matrix and generalized forces due to non-linear effects (gravity and velocity terms) and possibly the end-effector jacobians of my mathematical model with the matrices that MuJoCo computes during runtime.

Here's where I need some help: the coordinate frames of the generalized velocities, accelerations and forces of the free-floating joint are not completely clear to me but I know that they differ from the definitions I chose in my mathematical model. Thus, I need to know the definition used in MuJoCo to build the appropriate transforms that will allow me to compare the aforementioned elements of the equations of motion. I have read the documentation and checked previous issues quite thoroughly and I found scattered pieces of information from which I can guess some of these definitions (I believe most of them are in global coordinates) but I want some confirmation:

1 - From the documentation, I get that the qpos of this joint consists of the cartesian position of the body origin in global coordinates followed by the quaternion that represents its orientation. From what I read I assume that qvel, qacc and all the corresponding qfrc_ of this joint also present first the translational component and second the rotational one, can you confirm whether this is the case?

2 - Is the linear velocity in qvel expressed in local or global coordinates? If this is expressed in global coordinates, is this the time derivative of the position or the spatial velocity (as defined by Featherstone)?

3 - Same for the linear acceleration in qacc, is it expressed in local or global coordinates? If in global coordinates is this the second time derivative of the position or the spatial acceleration?

4 - Are the rotational velocity and acceleration (in qvel and qacc respectively) expressed in local or in global coordinates?

5 - I inferred from some simulation data that the forces in all qfrc_ are in global coordinates, but are the moments in local coordinates?

It's a lengthy post but I hope that I have posed my questions clearly. Otherwise, I'll be happy to rephrase. Thank you!

yuvaltassa commented 1 year ago

1 - From the documentation, I get that the qpos of this joint consists of the cartesian position of the body origin in global coordinates followed by the quaternion that represents its orientation.

No. I wonder where you got this idea from? This is only true for a body with a free joint, in which case the parent is the world and the coordinates are global. Otherwise joint are always expressed w.r.t the parent and are not Cartesian but Lagrangian.

It is very difficult to answer the rest of your questions as they appear to be predicated on this basic misunderstanding.

I recommend that you play with our tutorial notebook and maybe write some experimental code with very simple models. Once you have a specific question related to a specific, simple example model, ideally with a reproducible MWE, you can ask it here.

Anderv21 commented 1 year ago

@yuvaltassa Thank you for your fast response. Through my post I am only asking about the generalized velocities, accelerations and forces corresponding to a free joint, I am sorry if this was not explicit enough.

My question relates more to documentation (I think) than to coding itself, and I'll be happy to ask elsewhere if this is not the correct place.

My questions stem from the fact that you may choose to represent velocities of a free-floating body as a Twist/spatial velocity or as a 3D rotation and the time derivative of the body origin position, and you may also choose the coordinate frame in which these quantities are expressed. This also applies to 6D accelerations (linear/angular, Twist derivatives) and forces/moments/Wrenches.

Transforming from one representation to another is rather simple but you need to know what your starting point is. After reading the docs, the conventions used in MuJoCo for free-floating body velocities, accelerations and forces are not clear to me. Hence my questions. I'd appreciate it if you can answer, or let me know who else I can ask.

yuvaltassa commented 1 year ago

Ah, I see. Yes this was not clear in the OP.

  1. The linear DoFs of free joints are in the global frame, as are the linear velocities.
  2. The orientation of a free joint (a quaternion) is also in the global frame. However, the rotational velocities of a free joint are in the local frame. This is not so much a design decision but rather correctly following the topology of quaternions. Angular velocities live in the quaternion tangent space, which is defined locally for a certain orientation, so frame-local angular velocities are in some sense the natural parametrisation. You might gain more insight by examining MuJoCo's quaternion functions.
  3. All accelerations live in the same space as velocities.
  4. qfrc-type forces/torques live in the same space as accelerations, modulo the mass matrix. So for a free body with a diagonal mass matrix, a torque along one of the body's principal axes will lead to rotation only along that axis.
  5. mjData.xfrc_applied forces/torques, as you might guess by the x prefix, are in the global frame.

As an aside, is there a specific place in the documentation where you would expect to find this information? I'm happy to add a clarification in the appropriate place.

Cheers

PS In order to be 100% I didn't write anything wrong, I edited one of our colab tutorial cells to convince myself. You might find it useful, and I recommend using such toy examples to gain further understanding.

sample code for @Anderv21 ```py xml = """ """ model = mujoco.MjModel.from_xml_string(xml) data = mujoco.MjData(model) renderer = mujoco.Renderer(model) # enable joint visualization option: scene_option = mujoco.MjvOption() scene_option.flags[mujoco.mjtVisFlag.mjVIS_JOINT] = True duration = 3 # (seconds) framerate = 60 # (Hz) frames = [] mujoco.mj_resetData(model, data) # random orientation data.qpos[3:7] = np.random.randn(4) # MuJoCo will auto-normalise # apply torque along x-axis data.qfrc_applied[4] = 1 while data.time < duration: mujoco.mj_step(model, data) if len(frames) < data.time * framerate: renderer.update_scene(data, scene_option=scene_option) pixels = renderer.render().copy() frames.append(pixels) # Simulate and display video. media.show_video(frames, fps=framerate) ```
Anderv21 commented 1 year ago

Thank you for your response, it was very insightful and exactly what I needed.

Concerning the place in the documentation where I would expect this info, I would choose the Overview -> Kinematic tree -> Joint/DOF. Alternatively, adding the info in Overview -> Clarifications would also work. Other places that make sense to me are Modeling -> MJCF Mechanisms, and Computation -> General Framework -> The state. Thanks again!