Skip to content
This repository was archived by the owner on Nov 26, 2020. It is now read-only.
Jemin Hwangbo edited this page Apr 28, 2020 · 4 revisions

Q & A

1. How to get contact force?

RaiSim uses a velocity-based simulation scheme and there it only provides contact impulses. Users should divide it by the time step in order to get the average force applied over the time step. In addition, the impulse is defined in the contact frame. A description of the contact frame can be found in the manual.

Here is an example (using ANYmal model)

    /// Let's check all contact impulses acting on "LF_SHANK"
    auto footIndex = anymal_->getBodyIdx("LF_SHANK");

    /// for all contacts on the robot, check ...
    for(auto& contact: anymal_->getContacts()) {
      if ( footIndex == contact.getlocalBodyIndex() ) {
        std::cout<<"Contact impulse in the contact frame: "<<contact.getImpulse()->e()<<std::endl;
        std::cout<<"Contact frame: \n"<<contact.getContactFrame()->e()<<std::endl;
        std::cout<<"Contact impulse in the world frame: "<<contact.getContactFrame()->e() * contact.getImpulse()->e()<<std::endl;
        std::cout<<"Contact Normal in the world frame: "<<contact.getNormal().e().transpose()<<std::endl;
        std::cout<<"Contact position in the world frame: "<<contact.getPosition().e().transpose()<<std::endl;
        std::cout<<"It collides with: "<<world.getObject(contact.getPairObjectIndex().getName())<<std::endl;
        std::cout<<"please check Contact.hpp for the full list of the methods"<<std::endl; 
      }
    }

2. I get zero mass matrix or zero nonlinear term in an ArticulatedSystem

Please call integrate1() before accessing kinematic/dynamic properties.

3. I get an error "unknown body id" even if the body is defined

If multiple bodies are combined with fixed joints, only the topmost parent remains and the inertial properties of the other bodies are combined with the parent. If you want to get a position & orientation of a body, use Frames, which are attached to every joint. Bodies do not have a coordinate of their own. They just inherit one from their joint.

4. How can I set different material for each collision bodies?

Manual

5. How to get jacobians of a point

The Jacobian method getSparseJacobian takes position expressed in the world frame which is not useful for some use cases. If you want to pass the position expressed in the body frame, you have to compute the position in the world frame first. The following methods will be added in v1.0. I provide them as a reference.

/* This method only fills out non-zero elements. Make sure that the jaco is setZero() once in the initialization */
  void getDenseFrameJacobian(size_t frameIdx, Eigen::MatrixXd &jaco) {
    auto& frame = getFrameByIdx(frameIdx);
    Vec<3> position_W;
    getFramePosition(frameIdx, position_W);
    getDenseJacobian(frame.parentId, position_W, jaco);
  }

  /* This method only fills out non-zero elements. Make sure that the jaco is setZero() once in the initialization */
  void getDenseRotationalJacobian(size_t bodyIdx, Eigen::MatrixXd &jaco) {
    DRSFATAL_IF(jaco.rows() != 3 || jaco.cols() != dof, "Jacobian should be in size of 3XDOF")
    SparseJacobian sparseJaco;
    sparseJaco.resize(dof);
    getSparseRotationalJacobian(bodyIdx, sparseJaco);
    for (size_t i = 0; i < sparseJaco.size; i++)
      for (size_t j = 0; j < 3; j++)
        jaco(j, sparseJaco.idx[i]) = sparseJaco[i * 3 + j];
  }

Clone this wiki locally