Comparing two methods for obtaining the contact force on the object

Discussion in 'Simulation' started by yongxf, Sep 3, 2016.

  1. Hi,

    I am working on grasping project, and I am interested in how much force the hand gave to the object. In my situation, there are no other contacts apart from hand-object contact.

    I try to calculate the contact force in object frame. But the two methods that I used gave me different results.

    One method is to directly output the contact force on the object by: d->cfrc_ext+object_id*6. This will give me contact force in world frame. I can also convert the force to the object frame.

    Also, if we use mj_contactForce(m,d,i,f0_contact_force), we can get the contact force in contact frame, and then convert to the force in object frame.
    [​IMG]

    Here is the result:

    F1: -0.00002502 -0.00055801 5.24702777 0.00001662 -0.00000810 0.00000287 method 1: directly output force (represented in world frame)
    F2: 0.00172473 0.12709816 5.24548795 0.03522450 -0.00063034 0.00000656 method 1: the output force (represented in object frame)
    F3: 0.00172473 0.12709816 5.24548795 0.00001662 -0.00000803 0.00000306 method 2: map the contact force from contact frame to object frame

    If we compare F2 and F3, we will find that the first 3 elements are exactly the same, which is normal. However, the last three torques are quite different between each other. Especially for F2(4), F2(4) has dramatic difference, which will result in undesired behavior when lifting.

    If we check carefully, for the last three elements, F1 and F3 are actually close.

    I have checked all the adjoint transformation that I used for converting force from one frame to another, I am sure that they are correct.

    Do you know where the problem is?

    Thanks and best regards!
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    cfrc_ext is neither in the world frame nor in the object frame. Its frame orientation is aligned with the world frame, while its frame position is centered at the subtree center of mass, namely

    d->subtree_com+3*m->body_rootid[bodyid]

    Also, note that cfrc_ext is the sum of all contacts on the body, plus any external force from xfrc_applied. Are you sure there is only one active contact in your simulation? From the image it looks like there are multiple contacts.

    Assuming your conversion from the contact frame to the object frame is correct, F3 should be the correct contact force/torque.
     
    Samarth Brahmbhatt and Kyokushin like this.
  3. Hi, thanks for your reply.
    I have checked all the forces using the frame that you explained, and now they are exactly same.
    Actaully, I have four contacts in total. I sum all contact forces when using mj_contactForce(m,d,i,f0_contact_force). More concretely,
    \sum_{1}^{4}(Adjoint transform of the i-th point* the i-th f_contact_force_in_contact_frame). I assume there is no xfrc_applied in my simulation. Of course, I only used cfrc_ext to check my grasp calculation and I will not use it in the following calculation.

    Thanks a lot and your explanation really helps :D.
    Have a wonderful day!
    Best,
     
    Samarth Brahmbhatt and Kyokushin like this.