| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
|
|
| #ifndef MUJOCO_PLUGIN_SDF_NUT_H_ |
| #define MUJOCO_PLUGIN_SDF_NUT_H_ |
|
|
| #include <optional> |
|
|
| #include <mujoco/mjdata.h> |
| #include <mujoco/mjmodel.h> |
| #include <mujoco/mjtnum.h> |
| #include <mujoco/mjvisualize.h> |
| #include "sdf.h" |
|
|
| namespace mujoco::plugin::sdf { |
|
|
| |
| |
|
|
| struct NutAttribute { |
| static constexpr int nattribute = 1; |
| static constexpr char const* names[nattribute] = {"radius"}; |
| static constexpr mjtNum defaults[nattribute] = {0.26}; |
| }; |
|
|
| class Nut { |
| public: |
| |
| |
| static std::optional<Nut> Create(const mjModel* m, mjData* d, int instance); |
| Nut(Nut&&) = default; |
| ~Nut() = default; |
|
|
| void Reset(); |
| void Visualize(const mjModel* m, mjData* d, const mjvOption* opt, |
| mjvScene* scn, int instance); |
| void Compute(const mjModel* m, mjData* d, int instance); |
| mjtNum Distance(const mjtNum point[3]) const; |
| void Gradient(mjtNum grad[3], const mjtNum point[3]) const; |
|
|
| static void RegisterPlugin(); |
|
|
| mjtNum attribute[NutAttribute::nattribute]; |
|
|
| private: |
| Nut(const mjModel* m, mjData* d, int instance); |
|
|
| SdfVisualizer visualizer_; |
| }; |
|
|
| } |
|
|
| #endif |
|
|