Arm manipulation using d->ctrl

Discussion in 'Simulation' started by Karthik, Dec 12, 2016.

  1. I have developed mujoco model file for UR5 and used simulate and basic to visualize it. It works fine. In simulation, my robot arm lies on the ground plane. I tried to move it to a certain pose by setting d->ctrl value (required joint angles) before simulation and ran the simulation. But, the result is the same. No change in Pose. Is this method correct ? or Is there any other way to manipulate the joint angles(qpos) ? In future, I would like to supply the robot with a trajectory and simulate the same.
    ex: double control[8] = {0,-1.42,1.45,-3.14,1.46,0,-0.025,0.025}; d->ctrl=control;

    Based on this link:http://www.mujoco.org/forum/index.php?threads/directly-asign-joint-angles.3353/
    I manipulated the robot using d->qpos. At the start, it goes to the required pose and slowly falls to the ground plane. Is there any way to make it stay in that pose until the input for the next pose is given.
     
    Last edited: Dec 12, 2016
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    mjData.ctrl contains control signals for whatever actuators you have defined in the model. If you have position servos, setting mjData.ctrl will do what you want.

    mjData.qpos is the vector of joint angles. If you want to keep some of the joint angles constant, you have to set them after each simulation step, otherwise they will change according to the equations of motion.

    Note that if you want to set all joint angles all the time, this is no longer physics simulation; instead you are doing animation (which is a perfectly fine thing to do of course).
     
    OkayHuman likes this.
  3. Hi.. Thanks for the reply... I have used position servos in all my 6 hinge joints and I am using kp=100. In two joints, I am getting a large steady state error in joint angle (qpos). So, I increased the kp to 1000 but it still has some steady state error and it moves with a huge initial force. This is the actuator definition I am currently using
    <position name="shoulder_lift_act" joint="shoulder_lift_joint" kp="1000" ctrllimited="true" ctrlrange="-3.14159265 3.14159265"/>.
    To use user defined gainterm with 2 parameters (kp, ki) as in a PI controller in mjcb_act_gain(), I have defined actuator like this
    <general name="shoulder_lift" joint="shoulder_lift_joint" dyntype="none" gaintype="user" gainprm="1 .05"/>.
    But, I don't know how and where to assign and call gainterm[]=mjcb_act_gain(). I also need some help in implementing a integrator inside the mjcb_act_gain().
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    MuJoCo does not support PI actuators. You can assign two parameters to gainprm, as gainprm="1.05 0.76" for example, and use them however you want in the callback mjcb_act_gain(), but at the end this callback can only return one number. In general, all callbacks are function pointers, assigned somewhere in your code before you start the simulation.

    To implement a PI controller, you can define a P controller as you already did, and in addition generate applied force via qfrc_applied that implements the I term. This requires saving the integrated error somewhere. mjData.userdata is a good place for saving user-defined state variables.
     
  5. Thank you. I will try to implement your suggestion.