23 #include <mrpt/poses/CPose2D.h> 24 #include <mrpt/opengl/CSetOfObjects.h> 25 #include <mrpt/opengl/CSetOfLines.h> 26 #if MRPT_VERSION<0x199 27 #include <mrpt/utils/TColor.h> 28 using mrpt::utils::TColor;
30 #include <mrpt/img/TColor.h> 31 using mrpt::img::TColor;
56 double fx,
double fy,
double local_ptx = 0.0,
double local_pty = 0.0);
69 virtual double getMass()
const {
return m_mass; }
76 const mrpt::math::TPose3D&
getPose()
const 80 void setPose(
const mrpt::math::TPose3D& p)
const 83 const_cast<mrpt::math::TPose3D&
>(m_q) = p;
99 const mrpt::math::TPolygon2D&
getBlockShape()
const {
return m_block_poly; }
106 virtual void gui_update(mrpt::opengl::COpenGLScene& scene);
123 std::vector<b2FrictionJoint*> m_friction_joints;
132 mrpt::math::TPolygon2D m_block_poly;
134 double m_block_z_min, m_block_z_max;
136 TColor m_block_color;
137 mrpt::math::TPoint2D m_block_com;
139 double m_lateral_friction;
140 double m_ground_friction;
141 double m_restitution;
143 void updateMaxRadiusFromPoly();
149 void internal_gui_update_forces(
150 mrpt::opengl::COpenGLScene&
153 mrpt::opengl::CSetOfObjects::Ptr m_gl_block;
154 mrpt::opengl::CSetOfLines::Ptr m_gl_forces;
155 std::mutex m_force_segments_for_rendering_cs;
156 std::vector<mrpt::math::TSegment3D> m_force_segments_for_rendering;
vec3 getVelocityLocal() const
mrpt::math::TPoint2D getBlockCenterOfMass() const
In local coordinates.
virtual void apply_force(double fx, double fy, double local_ptx=0.0, double local_pty=0.0)
std::string m_name
User-supplied name of the block (e.g. "r1", "veh1")
const std::string & getName() const
virtual float getMaxBlockRadius() const
virtual double getMass() const
virtual void simul_post_timestep(const TSimulContext &context)
static void register_block_class(const rapidxml::xml_node< char > *xml_node)
void simul_post_timestep_common(const TSimulContext &context)
b2Body * getBox2DBlockBody()
const mrpt::math::TPose3D & getPose() const
const vec3 & getVelocity() const
A rigid body. These are created via b2World::CreateBody.
virtual void create_multibody_system(b2World *world)
virtual void gui_update(mrpt::opengl::COpenGLScene &scene)
static Block * factory(World *parent, const rapidxml::xml_node< char > *xml_node)
const mrpt::math::TPolygon2D & getBlockShape() const
void setPose(const mrpt::math::TPose3D &p) const
size_t getBlockIndex() const
void setBlockIndex(size_t idx)
mrpt::poses::CPose2D getCPose2D() const
virtual void simul_pre_timestep(const TSimulContext &context)