| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_ENGINE_ENGINE_COLLISION_PRIMITIVE_H_ |
| | #define MUJOCO_SRC_ENGINE_ENGINE_COLLISION_PRIMITIVE_H_ |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjexport.h> |
| | #include <mujoco/mjmodel.h> |
| |
|
| | |
| | #define mjGETINFO \ |
| | const mjtNum* pos1 = d->geom_xpos + 3*g1; \ |
| | const mjtNum* mat1 = d->geom_xmat + 9*g1; \ |
| | const mjtNum* size1 = m->geom_size + 3*g1; \ |
| | const mjtNum* pos2 = d->geom_xpos + 3*g2; \ |
| | const mjtNum* mat2 = d->geom_xmat + 9*g2; \ |
| | const mjtNum* size2 = m->geom_size + 3*g2; \ |
| | (void) size1; (void) size2; |
| |
|
| | #ifdef __cplusplus |
| | extern "C" { |
| | #endif |
| |
|
| | |
| | int mjraw_SphereCapsule (mjContact* con, mjtNum margin, |
| | const mjtNum* pos1, const mjtNum* mat1, const mjtNum* size1, |
| | const mjtNum* pos2, const mjtNum* mat2, const mjtNum* size2); |
| | int mjraw_CapsuleCapsule(mjContact* con, mjtNum margin, |
| | const mjtNum* pos1, const mjtNum* mat1, const mjtNum* size1, |
| | const mjtNum* pos2, const mjtNum* mat2, const mjtNum* size2); |
| | int mjraw_CapsuleBox (mjContact* con, mjtNum margin, |
| | const mjtNum* pos1, const mjtNum* mat1, const mjtNum* size1, |
| | const mjtNum* pos2, const mjtNum* mat2, const mjtNum* size2); |
| | int mjraw_SphereTriangle(mjContact* con, mjtNum margin, |
| | const mjtNum* s, mjtNum rs, |
| | const mjtNum* t1, const mjtNum* t2, const mjtNum* t3, mjtNum rt); |
| |
|
| | |
| | MJAPI int mjc_PlaneSphere (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| | MJAPI int mjc_PlaneCapsule (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| | MJAPI int mjc_PlaneCylinder (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| | MJAPI int mjc_PlaneBox (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| |
|
| | |
| | MJAPI int mjc_SphereSphere (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| | MJAPI int mjc_SphereCapsule (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| | MJAPI int mjc_SphereCylinder (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| | MJAPI int mjc_CapsuleCapsule (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| |
|
| | |
| | MJAPI int mjc_CapsuleBox (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| | MJAPI int mjc_SphereBox (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| | MJAPI int mjc_BoxBox (const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin); |
| |
|
| | #ifdef __cplusplus |
| | } |
| | #endif |
| | #endif |
| |
|