16 #include <mrpt/img/TColor.h> 17 #include <mrpt/math/TPolygon2D.h> 36 using Ptr = std::shared_ptr<Block>;
52 const mrpt::math::TVector2D& force,
147 {
"mass", {
"%lf", &m_mass}},
148 {
"zmin", {
"%lf", &m_block_z_min}},
150 {
"ground_friction", {
"%lf", &m_ground_friction}},
151 {
"lateral_friction", {
"%lf", &m_lateral_friction}},
152 {
"restitution", {
"%lf", &m_restitution}},
void blockShape(const mrpt::math::TPolygon2D &p)
virtual mrpt::poses::CPose3D internalGuiGetVisualPose() override
void poses_mutex_unlock() override
mrpt::math::TPoint2D getBlockCenterOfMass() const
In local coordinates.
std::map< std::string, TParamEntry > TParameterDefinitions
mrpt::math::TPoint2D m_block_com
In local coordinates.
void updateMaxRadiusFromPoly()
mrpt::opengl::CSetOfObjects::Ptr m_gl_block
virtual float getMaxBlockRadius() const
virtual double getMass() const
double block_z_min() const
void block_z_min(double v)
virtual void apply_force(const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) override
static Ptr factory(World *parent, const rapidxml::xml_node< char > *xml_node)
static void register_block_class(const rapidxml::xml_node< char > *xml_node)
const mrpt::math::TPolygon2D & blockShape() const
void mass(double newValue)
b2Body * getBox2DBlockBody()
std::shared_ptr< Block > Ptr
double m_lateral_friction
Default: 0.5.
A rigid body. These are created via b2World::CreateBody.
virtual void create_multibody_system(b2World &world)
mrpt::opengl::CSetOfLines::Ptr m_gl_forces
double ground_friction() const
double block_z_max() const
double m_ground_friction
Default: 0.5.
std::mutex m_force_segments_for_rendering_cs
void block_color(const mrpt::img::TColor &c)
std::vector< mrpt::math::TSegment3D > m_force_segments_for_rendering
virtual void simul_pre_timestep(const TSimulContext &context) override
mrpt::math::TPolygon2D m_block_poly
void block_z_max(double v)
double m_block_z_min
each change via updateMaxRadiusFromPoly()
virtual void internalGuiUpdate(mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override
size_t getBlockIndex() const
void internal_internalGuiUpdate_forces(mrpt::opengl::COpenGLScene &scene)
void setBlockIndex(size_t idx)
const TParameterDefinitions m_params
virtual void simul_post_timestep(const TSimulContext &context) override
mrpt::img::TColor m_block_color
void poses_mutex_lock() override
GLdouble GLdouble GLdouble b
double m_restitution
Deault: 0.01.
b2Fixture * m_fixture_block
const mrpt::img::TColor block_color() const
std::vector< b2FrictionJoint * > m_friction_joints
void ground_friction(double newValue)