Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Proposal for linear parametrization of inverse dynamics for SysID #1631

Open
lvjonok opened this issue May 3, 2024 · 6 comments
Open

Proposal for linear parametrization of inverse dynamics for SysID #1631

lvjonok opened this issue May 3, 2024 · 6 comments
Labels
enhancement New feature or request

Comments

@lvjonok
Copy link

lvjonok commented May 3, 2024

Hello MuJoCo Team,

I am currently finalizing my thesis in system identification (SysID) and adaptive control, together with @simeon-ned, we are working on SysID and adaptive control. We are very excited about the recent April update that introduced optimization and mentioned upcoming tutorials on SysID. Given our consistent use of MuJoCo for our research, we have developed a small GitHub repository dedicated to SysID in MuJoCo .

We have focused on the regressor representation, a linear parametrization of inverse dynamics, which is pivotal in SysID for robotic systems. To our knowledge, dedicated functions for this representation are not available in MuJoCo, prompting us to develop a prototype. Here are the main functions we introduced:

  • mj_bodyRegressor: This function calculates the regressor matrix for a single rigid body within a MuJoCo model.
  • mj_jointRegressor: This function calculates the regressor matrix for the entire inverse dynamics within a MuJoCo model.

Demo and Examples:

We have also included a demo notebook showcasing SysID in robotic systems using the regressor functions. Current examples include:

  • Estimation of cart-pole inertial parameters through random forcing and LQR stabilization.
  • Identification of the end-effector load for the Franka Emika Panda and compensation using inverse dynamics.
  • Determination of mass, center of mass, and spatial inertia for a Skydio X2 Quadrotor following trajectories via LTV LQR.

We plan to expand these examples to include more advanced techniques such as adaptive control, Riemannian regularization on parameter manifolds, physical consistency, and log-Cholesky inertia parametrization.

If you find this work useful and believe it deserves inclusion in the official MuJoCo engine and MJX, we would be delighted to contribute these capabilities further and assist in any way possible. Additionally, we are eager to enhance the demo notebook with more examples. We look forward to your feedback and hope to contribute meaningfully to the MuJoCo community.

Lastly, we want to express our gratitude for MuJoCo. We work with it daily and find it to be an incredibly convenient, powerful, and versatile tool.

@lvjonok lvjonok added the enhancement New feature or request label May 3, 2024
@yuvaltassa
Copy link
Collaborator

Hi!

What is a "body regressor" and "joint regressor"? You say "the regressor matrix for a single rigid body", I don't know what that is, please define it.

@simeon-ned
Copy link

simeon-ned commented May 5, 2024

Hello @yuvaltassa! Thanks for your reply!

In this context, a "regressor" refers to a matrix that linearly relates the inverse dynamics of a rigid body or a full mechanical system to its inertial parameters. These inertial parameters typically include the mass $m$, the first moment of mass (denoted as $m r_x, m r_y, m r_z$, and the elements of the inertia matrix $I_{xx}, I_{xy}, I_{yy}, I_{xz}, I_{yz}, I_{zz}$. We often represent these parameters as a vector, denoted by $\theta$.

The equation for inverse dynamics can thus be expressed in the form:

$$ M(q) \dot{v} + h(q, v) = Y(q, v, \dot{v}) \theta = Q $$

This framework is extensively utilized in fields such as adaptive control and system identification. One may also define such regressors on other mechanical quantities like energy, momentum, and power, discussed further in this paper.

We provide a short introduction to these concepts and list of related references in our Colab notebook. Additionally, implementation of these concepts can be found in our repository within the mujoco-sysid modeling.py.

@yuvaltassa
Copy link
Collaborator

Okay, let me see if I follow. Given the position, velocity and acceleration of a body or an entire mechanism, you rewrite the dynamics
$$M(q) \dot{v} + h(q, v) = \tau$$
as
$$Y(q, v, \dot{v}) \theta = \tau$$
Where the vector $\theta$ is effectively a rearrangement of the (unknown) inertia $M$, and $Y$ is the matrix that you compute. Given measurements of $q, v, \dot{v}$ and the computed matrix $Y$, the user can recover an estimate of the inertial parameters $\theta$.

Is this correct?

PS note that GH markdown supports LaTex 🙂

@simeon-ned
Copy link

Exactly so, you've got it right. And depending on the parameterization of the vector $\theta$, we can formulate the parameter estimates as simple linear least squares or more general nonlinear ones (solved for example, with mujoco.minimize)

PS: Thanks for the point about LaTeX, I've modified my comment above.

@lvjonok
Copy link
Author

lvjonok commented May 6, 2024

Moreover, it is not the only way to express parameterized dynamics linearly with respect to parameters. Energy and momentum of the system can be written linearly with respect to dynamical parameters too.

They are classified as acceleration-free models, so you need just $q, v$ to formulate a regressor in form $A(q, v) \theta = b$.

@chinahuangyong
Copy link

chinahuangyong commented May 6, 2024

Good job! I also have some similar work, but the simulator tool is matlab.

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
None yet
Development

No branches or pull requests

4 participants