| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_PLUGIN_SDF_TORUS_H_ |
| | #define MUJOCO_PLUGIN_SDF_TORUS_H_ |
| |
|
| | #include <optional> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjtnum.h> |
| | #include "sdf.h" |
| |
|
| | namespace mujoco::plugin::sdf { |
| |
|
| | struct TorusAttribute { |
| | static constexpr int nattribute = 2; |
| | static constexpr char const* names[nattribute] = {"radius1", "radius2"}; |
| | static constexpr mjtNum defaults[nattribute] = { .35, .15 }; |
| | }; |
| |
|
| | class Torus { |
| | public: |
| | |
| | static std::optional<Torus> Create(const mjModel* m, mjData* d, int instance); |
| | Torus(Torus&&) = default; |
| | ~Torus() = default; |
| |
|
| | mjtNum Distance(const mjtNum point[3]) const; |
| | void Gradient(mjtNum grad[3], const mjtNum point[3]) const; |
| |
|
| | static void RegisterPlugin(); |
| |
|
| | mjtNum attribute[TorusAttribute::nattribute]; |
| |
|
| | private: |
| | Torus(const mjModel* m, mjData* d, int instance); |
| | }; |
| |
|
| | } |
| |
|
| | #endif |
| |
|