Gear coupling?

Discussion in 'Priority support' started by rubstar, Feb 10, 2020.

  1. I'm working on a 1 DoF gripper. Is it possible to couple the two jaws using a "virtual" gear? I want the jaws to be kinematically constrained, and have just 1 actuator.

    This is what the gripper looks like:

    upload_2020-2-10_17-34-22.png

    upload_2020-2-10_17-35-3.png
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

  3. Hi Emo,

    I see the equality constraints, and I'm using them for the 4-bar linkage, but it's not clear how to couple the two driving actuators into one. I've highlighted where the actuators sit and attached the .xml for this particular setup.
    upload_2020-2-11_9-55-45.png
     

    Attached Files:

  4. So I was able to solve the above problem using the "coupling" equality, but now I have an issue with numerical stability using solref for the anchor links that complete the kinematic chain. I want the position of the anchor to be as rigid as possible, so I'm using solref="-1000000 -1000". The problem is as the stiffness terms gets large, I start to lose stability. Any advice on fixing this. Attached is the .xml
     

    Attached Files:

  5. Emo Todorov

    Emo Todorov Administrator Staff Member

    Large stiffness always leads to instability when integrating ODEs. You could make the step size smaller or use RK4, but it is better to reduce the stiffness. Also, did you try positive numbers for solref?
     
  6. Thanks Emo,

    Is there another approach for closing the kinematic chain other than using an anchor equality constraint?
     
  7. Emo Todorov

    Emo Todorov Administrator Staff Member

    You have to use a constraint, no matter how you formulate the kinematics and dynamics of the system. MuJoCo uses minimal coordinates where some constraints are imposed by the kinematic tree and cannot be violated, while the rest have to be imposed numerically. The alternative is to use over-complete representations where all constraints are imposed numerically.

    The only way around this is to explicitly construct a (nonlinear) coordinate system over the manifold of configurations satisfying the constraints, and express the physics in those coordinates. Then constraint violations will never occur. However you would have to do a lot of math and coding for every new system; basically you will be deriving new equations of motion (on the bright side, the resulting equations will be named after you:) The point of a physics engine is to avoid this effort and automate the process as much as possible.

    If you can always reduce constraint violations by decreasing the time step and increasing the stiffness, but the simulation slow down.
     
  8. Emo Todorov

    Emo Todorov Administrator Staff Member

    There is actually one more thing you can do: project the state on the constraint manifold after each simulation step. In other words, make a change to qpos such that the constraint violation is exactly zero. mj_forward computes the constraint violations and their Jacobians, so you can implement an optimization algorithm that drives the constraints to zero and call it after each simulation step. You would also have to make sure that qvel is tangent to the constraint manifold (this is more complicated and you may need finite difference approximations). This amounts to injecting some novel dynamics into the equations of motion... so it is a hack, although some hacks can be useful.
     
  9. Awesome, thanks for the detailed replies Emo!