Contact and Collision¶
Collision Group and Mask¶
Collision group and mask in RaiSim uses bit operations as most other physics engines. The below example is self-explanatory
raisim::World world;
auto sphere0 = world.addSphere(1, 1, raisim::COLLISION(0), raisim::COLLISION(0) | raisim::COLLISION(1));
auto sphere1 = world.addSphere(1, 1, raisim::COLLISION(1), raisim::COLLISION(0) | raisim::COLLISION(1));
auto sphere2 = world.addSphere(1, 1, raisim::COLLISION(2), raisim::COLLISION(1));
auto sphere3 = world.addSphere(1, 1, raisim::COLLISION(3), -1);
In the above example, sphere0 is in collision group 0 and can collide with collision group 0 and 1.
sphere1 is in collision group 1 and can collide with collision group 0 and 1.
sphere2 is in collision group 2 and can collide with collision group 1.
sphere3 is in collision group 3 and can collide with any object (-1 means all groups).
The collision group and mask is AND logic. In order for A and B collide, A should be able to collide with B and vice versa.
sphere0 can collide with sphere1.
sphere1 cannot collide with spehre2 (both conditions must be satisfied).
sphere3 cannot collide with any objects (because sphere0, sphere1 and sphere2 cannot collide with the collision group 3).
By default, movable object are in collision group 1 and can collide with anything (collision mask = -1). All static objects (e.g., ground and height map) are by default in collision group 63 and can collide with anything.
Contacts¶
raisim::Object (and thus raisim::ArticulatedSystem and raisim:SingleBodyObject) have a method getContacts which returns the list of contacts.
For example,
auto& contactsOnAnymal = anymal->getContacts();
Contact class is header-only and can be found at include/raisim/contact/Contact.hpp.
Note that all vector quantities are expressed in the respective Contact Frame. A contact frame is defined such that its z-axis is colinear with the contact normal and its origin is at the contact point. Its x- and y-axes are chosen arbitrary. Here is an extensive example
/// 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 (contact.skip()) continue; /// if the contact is internal, one contact point is set to 'skip'
if ( footIndex == contact.getlocalBodyIndex() ) {
std::cout<<"Contact impulse in the contact frame: "<<contact.getImpulse()->e()<<std::endl;
/// the impulse is acting from objectB to objectA. You can check if this object is objectA or B by
std::cout<<"is ObjectA: "<<contact.isObjectA()<<std::endl;
std::cout<<"Contact frame: \n"<<contact.getContactFrame().e().transpose()<<std::endl;
/// contact frame is transposed.
std::cout<<"Contact impulse in the world frame: "<<contact.getContactFrame().e().transpose() * 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())<<std::endl;
if (contact.getPairContactIndexInPairObject() != raisim::BodyType::STATIC) {
/// Static objects do not have Contacts store. So you must check if the pair object is static
/// This saves computation in raisim
world.getObject(contact.getPairObjectIndex()).getContacts(); /// You can use the same methods on the pair object
}
std::cout<<"please check Contact.hpp for the full list of the methods"<<std::endl;
}
}
API¶
You can get a vector of collisions on an object using raisim::Object::getContacts.
Each element in the vector has the following API:
-
class
Contact¶ Public Functions
-
inline const Vec<3> &
getPosition() const¶ the contact position
- Returns
the contact position
-
inline const Vec<3> &
getNormal() const¶ the contact normal vector pointing to ObjectA
- Returns
frame
-
inline const Mat<3, 3> &
getContactFrame() const¶ returns a TRANSPOSE of the frame that the impulse is expressed.
- Returns
contact frame
-
inline size_t
getIndexContactProblem() const¶ returns the corresponding index in raisim::World::getContactProblem
- Returns
contact index
-
inline size_t
getIndexInObjectContactList() const¶ returns the corresponding index in raisim::Object::getContacts
- Returns
contact index
-
inline size_t
getPairObjectIndex() const¶ returns the contacting object index in raisim::World::getObjectList
- Returns
object index
-
inline size_t
getPairContactIndexInPairObject() const¶ returns the contact index in the contacting (the paired) object in raisim::Object::getContacts This does not work if the pair body is STATIC because contacts on static bodies are not stored. First check the pair body type with getPairObjectBodyType
- Returns
contact index
-
inline const Vec<3> *
getImpulsePtr() const¶ returns the impulse pointer. You have to divide this number by the time step to get the force
- Returns
impulse
-
inline const Vec<3> &
getImpulse() const¶ returns the impulse. You have to divide this number by the time step to get the force
- Returns
impulse
-
inline bool
isObjectA() const¶ returns if the object is objectA. When there is a contact, the two paired objects are assigned to be objectA and objectB arbitrarily. The contact frame is defined such that its z-axis is pointing towards the objectA. The contact impulse is defined as an external force that objectA experiences.
- Returns
impulse
-
inline BodyType
getPairObjectBodyType() const¶ returns the body type of the paired object. Please read https://raisim.com/sections/Object.html#body-types to learn about it
- Returns
the body type
-
inline Mat<3, 3> &
getInvInertia()¶ returns the inverse apparent inertia of the contacting point
- Returns
inertia
-
inline size_t
getlocalBodyIndex() const¶ get local body index of this contact. The local index is assigned to each moving body in an object
- Returns
the body index.
-
inline double
getDepth() const¶ The penetration depth of the contact
- Returns
the depth of the contact
-
inline bool
isSelfCollision() const¶ returns if the contact is self collision
- Returns
if this is a self collision
-
inline bool
skip() const¶ this is set true for one self-collision point so that you don’t count them twice
- Returns
if you can skip this contact point while iterating contact points
-
inline dGeomID
getCollisionBodyA()¶ get the collision body of this object. This is ODE interface
- Returns
collision body
-
inline dGeomID
getCollisionBodyB()¶ get the collision body of the pairing object. This is ODE interface
- Returns
collision body
-
inline const Vec<3> &