Geometric jacobian for joint positions instead of velocities

Discussion in 'Simulation' started by Robert, Apr 24, 2020.

  1. mj_jac() and related functions provide a geometric ("end-effector") jacobian. The result is (3 x nv) and could be used as:
    [​IMG]
    (Where v is qvel and q is qpos)
    I.e. to calculate some end-effector velocity based on joint velocity.

    However, for my current application I need a jacobian for qpos. (For a model with quaternions, so it is not easily related to qvel). I specifically need the jacobian according to the classic definition:
    [​IMG]
    [​IMG]

    Is there way to find this position geometric jacobian instead of the velocity geometric jacobian?
     
  2. Sort of found a solution based on converting quaternions rates to angular velocities and visa-versa. Not exactly convenient.

    I decided to fall back on the differentiate and integrate functions of MuJoCo to convert joint rates (derivative of qpos) to joint velocities (qvel):

    Code:
    // Pseudo code
    
    // qvel to qpos_dot:
    qpos_dot = (mj_integratePos(m, qpos, qvel, dt) - qpos) / dt;
    
    // qpos_dot to qvel:
    qvel = mj_differentiatePos(m, qpos, qpos + qpos_dot * dt, dt)
    
    Not exactly ideal. Still looking for if the underlying conversions are exposed somewhere.
     
  3. Hello Robert,

    will you be able to share how you utilize mj_jac() for end-effector ik calculation? I am dealing with shadow hand and tried to move mocap on fingertips to realize that but seemed failed so now looking into mj_jac(). I am wondering if one mj_jac() can compute joint states for multiple end-effectors' (fingertips) specific position input. Thank you very much.
     
  4. Yeah, though what exactly is your question?

    You can find my inverse kinematics solution here: https://bitbucket.org/mscassignmentrobert/mujoco-tools/src/master/src/MuJoCoModel.cpp#lines-523
    It is part of a larger MuJuCo wrapper. It's not exactly easy to read, sorry about that.
    In this implementation I find the position jacobians numerically, and use them to iteratively solve an IK problem.
    EDIT: I was mistaken, I actually use the analytical geometric jacobian from mj_jac(), since I compute control velocities first.
     
    Last edited: May 19, 2020
    Jeff_hgrx likes this.