google-deepmind / mujoco

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

How to simulate a constant speed conveyor belt? #547

Closed joaopfg closed 1 year ago

joaopfg commented 1 year ago

Hi, I am a beginner in Mujoco. I'm using the C API and I want to simulate a constant speed conveyor belt. For this, a first model I want to try is a static box in the ground, with a force field applied in a particular direction in a rectangular parallelepiped just above it and a damping in the opposite direction so that I get the speed constant when the damping becomes equal to the force (like a free body falling through the air). What is the easiest way to simulate it using Mujoco's C API ? Any simpler idea to simulate a constant speed conveyor belt ?

Thanks in advance

quagla commented 1 year ago

Hi, do you actually want to model the belt or do you only care that the objects are moving? I believe with your suggestion you also want to remove friction so that objects are sliding on the ground or did I get your description incorrectly?

joaopfg commented 1 year ago

@quagla Hi, my final goal is to get something closer to a real belt. But since I'm a beginner with Mujoco and with this kind of modelling, I'm trying to be less ambitious for now and just get a simpler model in which the objects move. Yes, you are right, I also need to remove friction to get the constant speed in the model I mentioned.

I guess my main difficult is to restrict the force field to a particular region in the space. I can already get a force field in all the space by modifying the gravity vector, for example. I also have doubts about the damping. Should it appear in the XML file or when I call Mujoco's API at runtime ?

quagla commented 1 year ago

You may want to play with this file to start with:

https://github.com/deepmind/mujoco/blob/main/test/engine/testdata/activation.xml

Turn on Actuator and Activation in the Rendering panel to understand what is going on. Activation is coloring the actuator with the value of the internal state so it will give you an indication of when the body is about to accelerate after you increase an input with the sliders. You probably want something similar to the slider site but tangential to the face. You should be able to do all these changes in the XML.

yuvaltassa commented 1 year ago

What you are proposing is basically the right thing. Make a long box (possibly a series of adjacent boxes would be better for collision detection), give it a slider joint with large damping and add a general actuator. By doing something like

<actuator>
  <general joint="conveyor" gainprm="0" biasprm="x">
</actuator>

You will get an actuator that exerts a constant force x, but whose control signal does nothing (unless you want to control the conveyor speed, in which case don't zero out the gain). Read more about the actuation model here.

One additional trick that might be useful, if you need you conveyor to run for a long time, you can manually (in code) make the slider value jump back to the beginning after it reaches some threshold. This will not affect the contacts (since you won't touch the velocity), so the sim will continue as if nothing happened. This will give you an "infinite" conveyor.

Feel free to post your test models here if something doesn't make sense.

joaopfg commented 1 year ago

@yuvaltassa @quagla Thanks for help. I'm having a hard time trying to understand the ideas. I will try to highlight the points which I'm not understanding.

So, if I understood, I can attach a joint to a body and, if the joint is of type slide, it restricts the movement of the body to the direction of a fixed vector in the space.

Then, I can attach an actuator to the joint. The actuator has a length li(q) defined by the type of transmission and its parameters. * What is the intuition behind naming li as length ?

The gradient ∇li is an nv-dimensional vector of moment arms. What does it mean ? Could you describe a bit more or point me to some learning resource, please ?

The actuator is a function that receives an input ui (which I can control in the code), an activation state wi and outputs a force pi according to the formula pi = (awi or aui) + b0 + b1li + b2li(.). What is the intuition behind the activation state ? Can you give me some intuition about why the formula is like this, please ?

The force pi is mapped to joint coordinates by a vector of moment arms determined by the transmission. If I understand the mapping takes pi and ∇li and gives ∇li * pi , right ? What is the intuition behind that ?

I guess I'm missing some theory. I would appreciate if you can indicate me some learning resources to understand all this better .

yuvaltassa commented 1 year ago

So, if I understood, I can attach a joint to a body and, if the joint is of type slide, it restricts the movement of the body to the direction of a fixed vector in the space.

Correct.

Then, I can attach an actuator to the joint. The actuator has a length li(q) defined by the type of transmission and its parameters. * What is the intuition behind naming li as length ?

Correct. $l$ stands for "length" and $l_i$ means "the length of actuator $i$".

The gradient ∇li is an nv-dimensional vector of moment arms. What does it mean ? Could you describe a bit more or point me to some learning resource, please ?

The moment arm matrix is the analytic Jacobian of the length vector. This is a nu x nv matrix of which each row is the gradient $\frac{\partial l_i}{\partial q}$.

The actuator is a function that receives an input ui (which I can control in the code), an activation state wi and outputs a force pi according to the formula pi = (awi or aui) + b0 + b1li + b2li(.). What is the intuition behind the activation state ? Can you give me some intuition about why the formula is like this, please ?

The activation state is an optional internal state of the actuator. MuJoCo natively supports integrators and filters. You don't need this.

The force pi is mapped to joint coordinates by a vector of moment arms determined by the transmission. If I understand the mapping takes pi and ∇li and gives ∇li * pi , right ? What is the intuition behind that ?

The moment arm matrix projects from forces in actuator space (mjData.actuator_force) to the joint space (mjData.qfrc_actuator).

I guess I'm missing some theory. I would appreciate if you can indicate me some learning resources to understand all this better .

I recommend reading mj_fwdActuation.

joaopfg commented 1 year ago

@yuvaltassa Thanks. How is the actuator length calculated ?

I tried a proof concept based on what you said but can't get the conveyor moving.

Here is the XML:

<mujoco>
    <compiler autolimits="true"/>
    <option density="1000"/>

    <worldbody>
        <geom type="plane" size="10 10 .1" rgba="1 1 1 1"/>
        <light pos="0 0 20"/>
        <body pos="0 0 1">
            <geom type="box" size="1 5 1"/>
            <joint name="conveyor" type="slide" pos="0 -10 0" axis="0 1 0" damping="1000"/>
        </body>
        <body pos="0 0 3">
            <geom type="box" size="1 1 1"/>
            <freejoint/>
        </body>
    </worldbody>

    <actuator>
        <general name="conveyor" joint="conveyor" gainprm="0" biasprm="10000"/>
    </actuator>
</mujoco>

If I set the gainrpm instead of biasrpm, I can move the conveyor by passing a non-zero control input though. What is the problem ?

yuvaltassa commented 1 year ago

My bad, you need to add biastype="affine", the default is none so you bias gets ignored. See docs here

joaopfg commented 1 year ago

@yuvaltassa Thanks, what about the actuator length ? Is it calculated when the body moves with respect to the joint position ? I can't find this calculation in the source code, but I am printing it and I see that it increases when the conveyor moves. Can you point me to the method, please ? Does it mean, the force will grow indefinitely as the conveyor moves ?

I also have some doubts about the damping. What API method should I use to change it programmatically ? I want to be able to stop the conveyor immediately when the control input gets to zero. I am thinking about doing it by setting a very high damping during a short moment and then returning to the previous damping once the movement in the opposite sense starts.

yuvaltassa commented 1 year ago

Method is here.

mjModel.dof_damping[i] = x