| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_ENGINE_ENGINE_COLLISION_DRIVER_H_ |
| | #define MUJOCO_SRC_ENGINE_ENGINE_COLLISION_DRIVER_H_ |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjexport.h> |
| | #include <mujoco/mjmodel.h> |
| |
|
| | #ifdef __cplusplus |
| | extern "C" { |
| | #endif |
| |
|
| | |
| | MJAPI extern mjfCollision mjCOLLISIONFUNC[mjNGEOMTYPES][mjNGEOMTYPES]; |
| |
|
| | |
| | MJAPI void mj_collision(const mjModel* m, mjData* d); |
| |
|
| | |
| | MJAPI int mj_collideOBB(const mjtNum aabb1[6], const mjtNum aabb2[6], |
| | const mjtNum xpos1[3], const mjtNum xmat1[9], |
| | const mjtNum xpos2[3], const mjtNum xmat2[9], mjtNum margin, |
| | mjtNum product[36], mjtNum offset[12], mjtByte* initialize); |
| |
|
| | |
| | MJAPI int mj_isElemActive(const mjModel* m, int f, int e); |
| |
|
| | |
| | void mj_collideGeomPair(const mjModel* m, mjData* d, int g1, int g2, int merged, |
| | int startadr, int pairadr); |
| |
|
| | |
| | void mj_collideTree(const mjModel* m, mjData* d, int bf1, int bf2, |
| | int merged, int startadr, int pairadr); |
| |
|
| | |
| | int mj_broadphase(const mjModel* m, mjData* d, int* bfpair, int maxpair); |
| |
|
| | |
| | void mj_collideGeoms(const mjModel* m, mjData* d, int g1, int g2); |
| |
|
| | |
| | void mj_collidePlaneFlex(const mjModel* m, mjData* d, int g, int f); |
| |
|
| | |
| | void mj_collideFlexInternal(const mjModel* m, mjData* d, int f); |
| |
|
| | |
| | void mj_collideFlexSAP(const mjModel* m, mjData* d, int f); |
| |
|
| | |
| | void mj_collideGeomElem(const mjModel* m, mjData* d, int g, int f, int e); |
| |
|
| | |
| | void mj_collideElems(const mjModel* m, mjData* d, int f1, int e1, int f2, int e2); |
| |
|
| | |
| | void mj_collideElemVert(const mjModel* m, mjData* d, int f, int e, int v); |
| |
|
| |
|
| | #ifdef __cplusplus |
| | } |
| | #endif |
| |
|
| | #endif |
| |
|