Simple Position Servo

Discussion in 'Simulation' started by Siebe, Nov 17, 2016.

  1. Hi

    I am trying to include a position servo in my robot model but I am having trouble figuring out the relation between the control signal, gear setting and the actual position of the servo.

    I created a small example with a positional servo and an arm to indicate the servo position.


    HTML:
    <mujoco model="servo">
      <compiler angle="degree" coordinate="global" inertiafromgeom="true"/>
      <default>
        <geom rgba=".9 .7 .1 1" size="0.05"/>
        <joint axis="0 0 1" limited="false" solimplimit="0.95 0.95 0.1" type="hinge"/>
      </default>
     
      <worldbody>
        <body>
          <geom density="1" pos="0 0 0.1" size=".1 .1 .1" type="box"/>
          <body>
            <geom fromto="0 0 .2 .5 0 .2" type="capsule"/>
            <joint name="servo_1" pos="0 0 .1"/>
          </body>
        </body>
      </worldbody>
     
      <actuator>
        <position ctrllimited="true" ctrlrange="0 360" gear="1" joint="servo_1"/>
      </actuator>
    </mujoco>
    I am controlling this model using mujoco-py, so I am still using version 1.31. I do this by setting the model.data.ctrl to what I believe are angles for the servo position. I then step multiple times until the joint (servo) stops moving. But the resulting position is not what I expected.

    Can you help me with this? What range should the control signal be in and what about the gear setting?

    Thanks in advance,

    Siebe
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    Joint angles can be defined in degrees in the XML as you have done, but in the compiled/simulated models they are always in radians. The "ctrlrange" field is generic for all actuators, and the compiler does not recognize it as being in degrees. So you should expect to see angles in radians. Could this explain your results?

    The gear ratio is the mapping between joint angles (mjData.qpos) and servo positions (mjData.actuator_length). So if you specify gear=2 in the XML and set ctrl=0.1 at runtime, the joint angle should converge to qpos=0.2.
     
    tuonan and Kyokushin like this.
  3. Thank you for explaining, it makes sense now. The real problem was in my XML file, the servo arm (second body) was partially embedded in the base. Here is the updated xml I am working with right now:

    Code:
    <mujoco model="servo">
      <compiler angle="degree" coordinate="global" inertiafromgeom="true"/>
      <default>
        <geom rgba=".9 .7 .1 1" size="0.01"/>
        <joint axis="0 0 1" limited="false" solimplimit="0.95 0.95 0.1" type="hinge"/>
      </default>
    
      <worldbody>
        <body>
          <geom density="1" pos="0 0 0.1" size=".1 .1 .1" type="box"/>
          <body>
            <geom fromto="0 0 .25 .5 0 .25" type="capsule"/>
            <joint name="servo_1" pos="0 0 .1"/>
          </body>
        </body>
      </worldbody>
    
      <actuator>
        <position ctrllimited="false" ctrlrange="0 6.283185308" gear="1" joint="servo_1"/>
      </actuator>
    </mujoco>
    
    When I execute the following code in my c program:

    Code:
    // main loop
    while( d->time<duration ) {
            printf("time: %.3f\tctrl: %.7f\tqpos: %.7f\n", d->time, d->ctrl[0], d->qpos[0]);
    
            // Set actuator control
            d->ctrl[0] = mjPI;
          
            // advance simulation
            mj_step(m, d);
    }
    the qpos[0] oscillates back and forth around the ctrl position. It never gets to a stable state in the position I specified as control input. How is this possible? I simulated for a thousand seconds with timestep of 0.002
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    The position servo is a spring (with adjustable reference position). It is supposed to oscillate. Real servos do not oscillate because they also have damping and/or friction. You can add these properties to the joint.
     
    Kyokushin likes this.
  5. Hi, I read through the documentation and I am not sure about one thing in actuation model:
    upload_2018-4-19_1-11-17.png
    in this equation, grad(L_i) is explained as "column vector of moment arms". It looks like to me that this is similar "gear", as they both amplify the force generated. But L_i looks like the position of i-th actuator:
    upload_2018-4-19_1-13-55.png
    since you set b1 and b2 to implement PD position control. I am a little bit confused about this... So is L_i the position of i-th motor? Why does grad(L_i) come in as an force amplifier and how does "gear" play a role here?

    Thanks!
     
    Kyokushin likes this.
  6. Emo Todorov

    Emo Todorov Administrator Staff Member

    L_i is indeed the position of the i-th actuator (or length, when the actuator is attached to a tendon). Both grad(L) and the gear ratio amplify the actuator force. However grad(L) is a geometric property of the transmission, while the gear ratio is a parameter you can set. The difference is more clear when you consider an actuator acting on multiple DOFs (tendon, slider-crank). Then grad(L) is a vector which distributes the scalar actuator force to multiple DOFs, while the gear ratio is always a scalar.
     
  7. Also for position controlled actuators, if the required torque f exceeds the set maximum torque "forcerange", what will happen? It would be ideal if it automatically shuts down (like actual motors). It there any label variable that detects overtorque?

    Thanks!
     
    Last edited: Apr 21, 2018
  8. Emo Todorov

    Emo Todorov Administrator Staff Member

    It gets clipped at the maximum force instead of shutting down. There is no label. If you want to implement such functionality, disable the automatic clipping and implement it on your end - by monitoring mjData.actuator_force.