Block.h
Go to the documentation of this file.
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 #if MRPT_VERSION<0x199
00027 #include <mrpt/utils/TColor.h>
00028 using mrpt::utils::TColor;
00029 #else
00030 #include <mrpt/img/TColor.h>
00031 using mrpt::img::TColor;
00032 #endif
00033 
00034 namespace mvsim
00035 {
00038 class Block : public VisualObject, public Simulable
00039 {
00040    public:
00043         static Block* factory(
00044                 World* parent, const rapidxml::xml_node<char>* xml_node);
00046         static Block* factory(World* parent, const std::string& xml_text);
00047 
00050         static void register_block_class(const rapidxml::xml_node<char>* xml_node);
00051 
00052         // ------- Interface with "World" ------
00053         virtual void simul_pre_timestep(const TSimulContext& context);
00054         virtual void simul_post_timestep(const TSimulContext& context);
00055         virtual void apply_force(
00056                 double fx, double fy, double local_ptx = 0.0, double local_pty = 0.0);
00057 
00059         void simul_post_timestep_common(const TSimulContext& context);
00060 
00063         virtual void create_multibody_system(b2World* world);
00064 
00067         virtual float getMaxBlockRadius() const { return m_max_radius; }
00069         virtual double getMass() const { return m_mass; }
00070         b2Body* getBox2DBlockBody() { return m_b2d_block_body; }
00071         mrpt::math::TPoint2D getBlockCenterOfMass() const
00072         {
00073                 return m_block_com;
00074         }  
00075 
00076         const mrpt::math::TPose3D& getPose() const
00077         {
00078                 return m_q;
00079         }  
00080 
00081         void setPose(const mrpt::math::TPose3D& p) const
00082         {
00083                 const_cast<mrpt::math::TPose3D&>(m_q) = p;
00084         }  
00085 
00086 
00087         mrpt::poses::CPose2D getCPose2D() const;  
00088 
00090         const vec3& getVelocity() const { return m_dq; }
00093         vec3 getVelocityLocal() const;
00094 
00096         const std::string& getName() const { return m_name; }
00099         const mrpt::math::TPolygon2D& getBlockShape() const { return m_block_poly; }
00101         void setBlockIndex(size_t idx) { m_block_index = idx; }
00103         size_t getBlockIndex() const { return m_block_index; }
00106         virtual void gui_update(mrpt::opengl::COpenGLScene& scene);
00107 
00108    protected:
00109         // Protected ctor for class factory
00110         Block(World* parent);
00111 
00112         std::string
00113                 m_name;  
00114         size_t m_block_index;  
00115 
00116 
00122         b2Body* m_b2d_block_body;
00123         std::vector<b2FrictionJoint*> m_friction_joints;
00124 
00125         mrpt::math::TPose3D
00126                 m_q;  
00127         vec3 m_dq;  
00128 
00129 
00130         // Block info:
00131         double m_mass;
00132         mrpt::math::TPolygon2D m_block_poly;
00133         double m_max_radius;  
00134 
00135         double m_block_z_min, m_block_z_max;
00136         TColor m_block_color;
00137         mrpt::math::TPoint2D m_block_com;  
00138 
00139         double m_lateral_friction;  
00140         double m_ground_friction;  
00141         double m_restitution;  
00142 
00143         void updateMaxRadiusFromPoly();
00144 
00145         // Box2D elements:
00146         b2Fixture* m_fixture_block;
00147 
00148    private:
00149         void internal_gui_update_forces(
00150                 mrpt::opengl::COpenGLScene&
00151                         scene);  
00152 
00153         mrpt::opengl::CSetOfObjects::Ptr m_gl_block;
00154         mrpt::opengl::CSetOfLines::Ptr m_gl_forces;
00155         std::mutex m_force_segments_for_rendering_cs;
00156         std::vector<mrpt::math::TSegment3D> m_force_segments_for_rendering;
00157 
00158 };  // end Block
00159 }


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 22:08:35