#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. | |
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) |
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") |
A non-vehicle "actor" for the simulation, typically obstacle blocks.
Block::Block | ( | World * | parent | ) | [protected] |
void Block::apply_force | ( | double | fx, |
double | fy, | ||
double | local_ptx = 0.0 , |
||
double | local_pty = 0.0 |
||
) | [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.
void Block::create_multibody_system | ( | b2World * | world | ) | [virtual] |
Block * Block::factory | ( | World * | parent, |
const rapidxml::xml_node< char > * | root | ||
) | [static] |
Block * Block::factory | ( | World * | parent, |
const std::string & | xml_text | ||
) | [static] |
mrpt::math::TPoint2D mvsim::Block::getBlockCenterOfMass | ( | ) | const [inline] |
size_t mvsim::Block::getBlockIndex | ( | ) | const [inline] |
const mrpt::math::TPolygon2D& mvsim::Block::getBlockShape | ( | ) | const [inline] |
b2Body* mvsim::Block::getBox2DBlockBody | ( | ) | [inline] |
mrpt::poses::CPose2D Block::getCPose2D | ( | ) | const |
virtual double mvsim::Block::getMass | ( | ) | const [inline, virtual] |
virtual float mvsim::Block::getMaxBlockRadius | ( | ) | const [inline, virtual] |
const std::string& mvsim::Block::getName | ( | ) | const [inline] |
const mrpt::math::TPose3D& mvsim::Block::getPose | ( | ) | const [inline] |
const vec3& mvsim::Block::getVelocity | ( | ) | const [inline] |
vec3 Block::getVelocityLocal | ( | ) | const |
void Block::gui_update | ( | mrpt::opengl::COpenGLScene & | scene | ) | [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.
void Block::register_block_class | ( | const rapidxml::xml_node< char > * | xml_node | ) | [static] |
void mvsim::Block::setBlockIndex | ( | size_t | idx | ) | [inline] |
void mvsim::Block::setPose | ( | const mrpt::math::TPose3D & | p | ) | const [inline] |
void Block::simul_post_timestep | ( | const TSimulContext & | context | ) | [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 | ) |
void Block::simul_pre_timestep | ( | 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.
size_t mvsim::Block::m_block_index [protected] |
std::string mvsim::Block::m_name [protected] |