| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_ENGINE_ENGINE_CORE_CONSTRAINT_H_ |
| | #define MUJOCO_SRC_ENGINE_ENGINE_CORE_CONSTRAINT_H_ |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjexport.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjxmacro.h> |
| |
|
| | #ifdef __cplusplus |
| | extern "C" { |
| | #endif |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI int mj_isPyramidal(const mjModel* m); |
| |
|
| | |
| | MJAPI int mj_isSparse(const mjModel* m); |
| |
|
| | |
| | MJAPI int mj_isDual(const mjModel* m); |
| |
|
| | |
| | MJAPI void mj_mulJacVec(const mjModel* m, const mjData* d, mjtNum* res, const mjtNum* vec); |
| |
|
| | |
| | MJAPI void mj_mulJacTVec(const mjModel* m, const mjData* d, mjtNum* res, const mjtNum* vec); |
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_assignRef(const mjModel* m, mjtNum* target, const mjtNum* source); |
| |
|
| | |
| | void mj_assignImp(const mjModel* m, mjtNum* target, const mjtNum* source); |
| |
|
| | |
| | void mj_assignFriction(const mjModel* m, mjtNum* target, const mjtNum* source); |
| |
|
| | |
| | mjtNum mj_assignMargin(const mjModel* m, mjtNum source); |
| |
|
| | |
| | MJAPI int mj_addContact(const mjModel* m, mjData* d, const mjContact* con); |
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_instantiateEquality(const mjModel* m, mjData* d); |
| |
|
| | |
| | void mj_instantiateFriction(const mjModel* m, mjData* d); |
| |
|
| | |
| | void mj_instantiateLimit(const mjModel* m, mjData* d); |
| |
|
| | |
| | void mj_instantiateContact(const mjModel* m, mjData* d); |
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_diagApprox(const mjModel* m, mjData* d); |
| |
|
| | |
| | void mj_makeImpedance(const mjModel* m, mjData* d); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI void mj_makeConstraint(const mjModel* m, mjData* d); |
| |
|
| | |
| | MJAPI void mj_projectConstraint(const mjModel* m, mjData* d); |
| |
|
| | |
| | MJAPI void mj_referenceConstraint(const mjModel* m, mjData* d); |
| |
|
| | |
| | |
| | MJAPI void mj_constraintUpdate_impl(int ne, int nf, int nefc, |
| | const mjtNum* D, const mjtNum* R, const mjtNum* floss, |
| | const mjtNum* jar, const int* type, const int* id, |
| | mjContact* contact, int* state, mjtNum* force, mjtNum cost[1], |
| | int flg_coneHessian); |
| |
|
| | |
| | |
| | MJAPI void mj_constraintUpdate(const mjModel* m, mjData* d, const mjtNum* jar, |
| | mjtNum cost[1], int flg_coneHessian); |
| |
|
| |
|
| | #ifdef __cplusplus |
| | } |
| | #endif |
| |
|
| | #endif |
| |
|