| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_ENGINE_ENGINE_DERIVATIVE_FD_H_ |
| | #define MUJOCO_SRC_ENGINE_ENGINE_DERIVATIVE_FD_H_ |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjexport.h> |
| | #include <mujoco/mjmodel.h> |
| |
|
| | #ifdef __cplusplus |
| | extern "C" { |
| | #endif |
| |
|
| | |
| | MJAPI void mjd_smooth_velFD(const mjModel* m, mjData* d, mjtNum eps); |
| |
|
| | |
| | MJAPI void mjd_passive_velFD(const mjModel* m, mjData* d, mjtNum eps); |
| |
|
| | |
| | MJAPI void mj_stepSkip(const mjModel* m, mjData* d, int skipstage, int skipsensor); |
| |
|
| | |
| | MJAPI void mjd_transitionFD(const mjModel* m, mjData* d, mjtNum eps, mjtByte centered, |
| | mjtNum* A, mjtNum* B, mjtNum* C, mjtNum* D); |
| |
|
| | |
| | MJAPI void mjd_inverseFD(const mjModel* m, mjData* d, mjtNum eps, mjtByte flg_actuation, |
| | mjtNum *DfDq, mjtNum *DfDv, mjtNum *DfDa, |
| | mjtNum *DsDq, mjtNum *DsDv, mjtNum *DsDa, |
| | mjtNum *DmDq); |
| |
|
| | #ifdef __cplusplus |
| | } |
| | #endif |
| |
|
| | #endif |
| |
|