Skip to content
This repository was archived by the owner on Nov 26, 2020. It is now read-only.
jhwangbo edited this page Oct 18, 2019 · 11 revisions

RaiSim Wiki

All information here can be found in the manual as well. Please check the manual regularly since it is the only document that is meant to be a complete description of RaiSim.

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;
        /// the following method available as of sept 29th 2019
        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

Clone this wiki locally