| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
|
|
| #ifndef MUJOCO_SRC_ENGINE_ENGINE_COLLISION_SDF_H_ |
| #define MUJOCO_SRC_ENGINE_ENGINE_COLLISION_SDF_H_ |
|
|
| #include <mujoco/mjdata.h> |
| #include <mujoco/mjexport.h> |
| #include <mujoco/mjmodel.h> |
| #include <mujoco/mjplugin.h> |
| #include <mujoco/mjtnum.h> |
|
|
| #ifdef __cplusplus |
| extern "C" { |
| #endif |
|
|
| |
| MJAPI const mjpPlugin* mjc_getSDF(const mjModel* m, int id); |
|
|
| |
| MJAPI mjtNum mjc_distance(const mjModel* m, const mjData* d, const mjSDF* s, const mjtNum x[3]); |
|
|
| |
| MJAPI void mjc_gradient(const mjModel* m, const mjData* d, const mjSDF* s, mjtNum gradient[3], |
| const mjtNum x[3]); |
|
|
| |
| int mjc_HFieldSDF(const mjModel* m, const mjData* d, mjContact* con, int g1, int g2, mjtNum margin); |
|
|
| |
| int mjc_MeshSDF(const mjModel* m, const mjData* d, mjContact* con, int g1, int g2, mjtNum margin); |
|
|
| |
| int mjc_SDF(const mjModel* m, const mjData* d, mjContact* con, int g1, int g2, mjtNum margin); |
|
|
| #ifdef __cplusplus |
| } |
| #endif |
| #endif |
|
|