How to set the initial joint angles?

Discussion in 'Simulation' started by Chris Richards, Jun 15, 2016.

  1. I have a two link model with hinge joints. I would like to learn how to set the initial joint angles at time=0. I tried doing this using keyframe in the XML, but it doesn't seem to affect the simulation. I also tried this in the c code using mj_reset (as stated in the tutorial) or mj_resetData, neither of them worked either. What am I missing?
    Below is my XML code.

    Thanks for your time,
    Best,
    Chris

    Code:
    <mujoco model="example">
        <compiler coordinate="global"/>
        <size nkey="1" />
    
        <default>
            <geom rgba=".8 .6 .4 1"/>
        </default>
    
        <asset>
            <texture type="skybox" builtin="gradient" rgb1="1 1 1" rgb2=".6 .8 1" width="256" height="256"/>
        </asset>
    
        <worldbody>
            <light pos="0 1 1" dir="0 -1 -1" diffuse="1 1 1"/>
            <body>
                <geom type="capsule" fromto="0 0 0  0 0 -0.6" size="0.06"/>
                <joint name="j1" type="hinge" pos="0 0 0" axis="0 1 0"/>   
    <!--             <joint name="j1" type="ball" pos="0 0 1"/> -->
                <body>
                    <geom type="capsule" fromto="0 0 -0.6  0 0 -1" size="0.04"/>
                    <joint name="j2" type="hinge" pos="0 0 -0.6" axis="0 1 0"/>               
                </body>
            </body>
        </worldbody>
        <actuator>
       
            <!--  ================= Torque actuators ================= /-->
            <motor joint='j1'     name='Aj1' gear="100"/>
            <motor joint='j2'     name='Aj2' gear="100"/>
    
        </actuator>
        <sensor>
    
            <jointpos joint='j2' name='Sj2'/>
        </sensor>
        <keyframe>
            <key time="0" qpos="0.3 0.5" />
        </keyframe>
    </mujoco>
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    The keyframes defined in the model are for the user/programmer. The engine doesn't do anything with them directly, but you can use them to set the model state after the model is loaded:

    mju_copy(d->qpos, m->key_qpos, m->nq*keyframenumber);

    (and similarly for d->qvel and d->act)

    The function mj_reset always resets to the pose in which the model was defined, and sets the rest to 0. I should add a function like mj_instantiateKeyframe for doing this automatically...
     
  3. That's great, worked perfectly, thanks very much!
     
  4. Hao

    Hao

    Is it possible to set initial condition without keyframe?
    I have a bunch of joint position data and want to do position control. However, these data don't have the same starting point.
    I could write a function in c++ that reads these data in, but using
    Code:
    m->qpos0[index]=desired_pos
    won't work.
     
  5. Emo Todorov

    Emo Todorov Administrator Staff Member

  6. Hao

    Hao

    I wonder is it possible to set keyframe to only a few joints? Instead of setting all dof ?
     
  7. Emo Todorov

    Emo Todorov Administrator Staff Member

    No, this is not supported. You would have to write your own code for that. For example, you could use tuples to list the joints and the corresponding values in the model file, and then write code that scans the model for tuples with certain names and instantiates the joint angles in mjData.qpos
     
  8. Hao

    Hao

    Would you mind provide an example of using tuples? I am a little confused about how to combine it with keyframe.