00001 /*+-------------------------------------------------------------------------+ 00002 | Multiblock simulator (libmvsim) | 00003 | | 00004 | Copyright (C) 2014 Jose Luis Blanco Claraco (University of Almeria) | 00005 | Copyright (C) 2017 Borys Tymchenko (Odessa Polytechnic University) | 00006 | Distributed under GNU General Public License version 3 | 00007 | See <http://www.gnu.org/licenses/> | 00008 +-------------------------------------------------------------------------+ */ 00009 00010 #pragma once 00011 00012 #include <mvsim/basic_types.h> 00013 #include <mvsim/VisualObject.h> 00014 #include <mvsim/Simulable.h> 00015 #include <mvsim/ClassFactory.h> 00016 00017 #include <Box2D/Dynamics/b2World.h> 00018 #include <Box2D/Dynamics/b2Body.h> 00019 #include <Box2D/Collision/Shapes/b2PolygonShape.h> 00020 #include <Box2D/Dynamics/b2Fixture.h> 00021 #include <Box2D/Dynamics/Joints/b2FrictionJoint.h> 00022 00023 #include <mrpt/poses/CPose2D.h> 00024 #include <mrpt/opengl/CSetOfObjects.h> 00025 #include <mrpt/opengl/CSetOfLines.h> 00026 #include <mrpt/utils/TColor.h> 00027 00028 namespace mvsim 00029 { 00032 class Block : public VisualObject, public Simulable 00033 { 00034 public: 00037 static Block* factory( 00038 World* parent, const rapidxml::xml_node<char>* xml_node); 00040 static Block* factory(World* parent, const std::string& xml_text); 00041 00044 static void register_block_class(const rapidxml::xml_node<char>* xml_node); 00045 00046 // ------- Interface with "World" ------ 00047 virtual void simul_pre_timestep(const TSimulContext& context); 00048 virtual void simul_post_timestep(const TSimulContext& context); 00049 virtual void apply_force( 00050 double fx, double fy, double local_ptx = 0.0, double local_pty = 0.0); 00051 00053 void simul_post_timestep_common(const TSimulContext& context); 00054 00057 virtual void create_multibody_system(b2World* world); 00058 00061 virtual float getMaxBlockRadius() const { return m_max_radius; } 00063 virtual double getMass() const { return m_mass; } 00064 b2Body* getBox2DBlockBody() { return m_b2d_block_body; } 00065 mrpt::math::TPoint2D getBlockCenterOfMass() const 00066 { 00067 return m_block_com; 00068 } 00069 00070 const mrpt::math::TPose3D& getPose() const 00071 { 00072 return m_q; 00073 } 00074 00075 void setPose(const mrpt::math::TPose3D& p) const 00076 { 00077 const_cast<mrpt::math::TPose3D&>(m_q) = p; 00078 } 00079 00080 00081 mrpt::poses::CPose2D getCPose2D() const; 00082 00084 const vec3& getVelocity() const { return m_dq; } 00087 vec3 getVelocityLocal() const; 00088 00090 const std::string& getName() const { return m_name; } 00093 const mrpt::math::TPolygon2D& getBlockShape() const { return m_block_poly; } 00095 void setBlockIndex(size_t idx) { m_block_index = idx; } 00097 size_t getBlockIndex() const { return m_block_index; } 00100 virtual void gui_update(mrpt::opengl::COpenGLScene& scene); 00101 00102 protected: 00103 // Protected ctor for class factory 00104 Block(World* parent); 00105 00106 std::string 00107 m_name; 00108 size_t m_block_index; 00109 00110 00116 b2Body* m_b2d_block_body; 00117 std::vector<b2FrictionJoint*> m_friction_joints; 00118 00119 mrpt::math::TPose3D 00120 m_q; 00121 vec3 m_dq; 00122 00123 00124 // Block info: 00125 double m_mass; 00126 mrpt::math::TPolygon2D m_block_poly; 00127 double m_max_radius; 00128 00129 double m_block_z_min, m_block_z_max; 00130 mrpt::utils::TColor m_block_color; 00131 mrpt::math::TPoint2D m_block_com; 00132 00133 double m_lateral_friction; 00134 double m_ground_friction; 00135 double m_restitution; 00136 00137 void updateMaxRadiusFromPoly(); 00138 00139 // Box2D elements: 00140 b2Fixture* m_fixture_block; 00141 00142 private: 00143 void internal_gui_update_forces( 00144 mrpt::opengl::COpenGLScene& 00145 scene); 00146 00147 mrpt::opengl::CSetOfObjects::Ptr m_gl_block; 00148 mrpt::opengl::CSetOfLines::Ptr m_gl_forces; 00149 std::mutex m_force_segments_for_rendering_cs; 00150 std::vector<mrpt::math::TSegment3D> m_force_segments_for_rendering; 00151 00152 }; // end Block 00153 }