#include <Block.h>

| Public Member Functions | |
| virtual void | apply_force (double fx, double fy, double local_ptx=0.0, double local_pty=0.0) | 
| virtual void | create_multibody_system (b2World *world) | 
| mrpt::math::TPoint2D | getBlockCenterOfMass () const | 
| In local coordinates.  More... | |
| size_t | getBlockIndex () const | 
| const mrpt::math::TPolygon2D & | getBlockShape () const | 
| b2Body * | getBox2DBlockBody () | 
| mrpt::poses::CPose2D | getCPose2D () const | 
| virtual double | getMass () const | 
| virtual float | getMaxBlockRadius () const | 
| const std::string & | getName () const | 
| const mrpt::math::TPose3D & | getPose () const | 
| const vec3 & | getVelocity () const | 
| vec3 | getVelocityLocal () const | 
| virtual void | gui_update (mrpt::opengl::COpenGLScene &scene) | 
| void | setBlockIndex (size_t idx) | 
| void | setPose (const mrpt::math::TPose3D &p) const | 
| virtual void | simul_post_timestep (const TSimulContext &context) | 
| void | simul_post_timestep_common (const TSimulContext &context) | 
| virtual void | simul_pre_timestep (const TSimulContext &context) | 
|  Public Member Functions inherited from mvsim::VisualObject | |
| World * | getWorldObject () | 
| const World * | getWorldObject () const | 
| VisualObject (World *parent) | |
| virtual | ~VisualObject () | 
| Static Public Member Functions | |
| static Block * | factory (World *parent, const rapidxml::xml_node< char > *xml_node) | 
| static Block * | factory (World *parent, const std::string &xml_text) | 
| static void | register_block_class (const rapidxml::xml_node< char > *xml_node) | 
| Protected Member Functions | |
| Block (World *parent) | |
| Protected Attributes | |
| size_t | m_block_index | 
| std::string | m_name | 
| User-supplied name of the block (e.g. "r1", "veh1")  More... | |
|  Protected Attributes inherited from mvsim::VisualObject | |
| World * | m_world | 
A non-vehicle "actor" for the simulation, typically obstacle blocks.
| 
 | virtual | 
Override to register external forces exerted by other WorldElements. Force is (fx,fy) in global coordinates. Application point is (local_ptx,local_pty) in the body local frame
Reimplemented from mvsim::Simulable.
| 
 | virtual | 
| 
 | static | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| mrpt::poses::CPose2D Block::getCPose2D | ( | ) | const | 
| 
 | inlinevirtual | 
| 
 | inlinevirtual | 
| 
 | inline | 
| 
 | inline | 
| 
 | inline | 
| vec3 Block::getVelocityLocal | ( | ) | const | 
| 
 | virtual | 
Must create a new object in the scene and/or update it according to the current state.
To be called at derived classes' gui_update()
Implements mvsim::VisualObject.
| 
 | static | 
| 
 | inline | 
| 
 | inline | 
| 
 | virtual | 
Override to do any required process right after the integration of dynamic equations for each timestep
Reimplemented from mvsim::Simulable.
| void Block::simul_post_timestep_common | ( | const TSimulContext & | context | ) | 
| 
 | virtual | 
Process right before the integration of dynamic equations for each timestep: set action forces from motors, update friction models, etc.
Reimplemented from mvsim::Simulable.
| 
 | protected | 
| 
 | protected |