| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_ENGINE_ENGINE_PASSIVE_H_ |
| | #define MUJOCO_SRC_ENGINE_ENGINE_PASSIVE_H_ |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjexport.h> |
| | #include <mujoco/mjmodel.h> |
| |
|
| | #ifdef __cplusplus |
| | extern "C" { |
| | #endif |
| |
|
| | |
| |
|
| | |
| | MJAPI void mj_passive(const mjModel* m, mjData* d); |
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_inertiaBoxFluidModel(const mjModel* m, mjData* d, int i); |
| |
|
| | |
| | void mj_ellipsoidFluidModel(const mjModel* m, mjData* d, int bodyid); |
| |
|
| | |
| | void mj_addedMassForces( |
| | const mjtNum local_vels[6], const mjtNum local_accels[6], |
| | mjtNum fluid_density, const mjtNum virtual_mass[3], |
| | const mjtNum virtual_inertia[3], mjtNum local_force[6]); |
| |
|
| | |
| | void mj_viscousForces( |
| | const mjtNum local_vels[6], mjtNum fluid_density, |
| | mjtNum fluid_viscosity, const mjtNum size[3], |
| | mjtNum magnus_lift_coef, mjtNum kutta_lift_coef, |
| | mjtNum blunt_drag_coef, mjtNum slender_drag_coef, |
| | mjtNum ang_drag_coef, mjtNum local_force[6]); |
| |
|
| | void readFluidGeomInteraction(const mjtNum* geom_fluid_coefs, |
| | mjtNum* geom_fluid_coef, |
| | mjtNum* blunt_drag_coef, |
| | mjtNum* slender_drag_coef, |
| | mjtNum* ang_drag_coef, |
| | mjtNum* kutta_lift_coef, |
| | mjtNum* magnus_lift_coef, |
| | mjtNum virtual_mass[3], |
| | mjtNum virtual_inertia[3]); |
| |
|
| | void writeFluidGeomInteraction (mjtNum* geom_fluid_coefs, |
| | const mjtNum* geom_fluid_coef, |
| | const mjtNum* blunt_drag_coef, |
| | const mjtNum* slender_drag_coef, |
| | const mjtNum* ang_drag_coef, |
| | const mjtNum* kutta_lift_coef, |
| | const mjtNum* magnus_lift_coef, |
| | const mjtNum virtual_mass[3], |
| | const mjtNum virtual_inertia[3]); |
| |
|
| |
|
| | #ifdef __cplusplus |
| | } |
| | #endif |
| |
|
| | #endif |
| |
|