Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes
mvsim::Block Class Reference

#include <Block.h>

Inheritance diagram for mvsim::Block:
Inheritance graph
[legend]

List of all members.

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
b2BodygetBox2DBlockBody ()
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 vec3getVelocity () 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 Blockfactory (World *parent, const rapidxml::xml_node< char > *xml_node)
static Blockfactory (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")

Detailed Description

A non-vehicle "actor" for the simulation, typically obstacle blocks.

Definition at line 32 of file Block.h.


Constructor & Destructor Documentation

Block::Block ( World parent) [protected]

Definition at line 34 of file Block.cpp.


Member Function Documentation

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.

Definition at line 426 of file Block.cpp.

void Block::create_multibody_system ( b2World world) [virtual]

Create bodies, fixtures, etc. for the dynamical simulation. May be overrided by derived classes

Create bodies, fixtures, etc. for the dynamical simulation

Definition at line 348 of file Block.cpp.

Block * Block::factory ( World parent,
const rapidxml::xml_node< char > *  root 
) [static]

Class factory: Creates a block from XML description of type "<block>...</block>".

Class factory: Creates a vehicle from XML description of type "<vehicle>...</vehicle>".

Definition at line 104 of file Block.cpp.

Block * Block::factory ( World parent,
const std::string &  xml_text 
) [static]

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 239 of file Block.cpp.

mrpt::math::TPoint2D mvsim::Block::getBlockCenterOfMass ( ) const [inline]

In local coordinates.

Definition at line 65 of file Block.h.

size_t mvsim::Block::getBlockIndex ( ) const [inline]

Get the block index in the World

Definition at line 97 of file Block.h.

const mrpt::math::TPolygon2D& mvsim::Block::getBlockShape ( ) const [inline]

Get the 2D shape of the block, as set from the config file (only used for collision detection)

Definition at line 93 of file Block.h.

Definition at line 64 of file Block.h.

mrpt::poses::CPose2D Block::getCPose2D ( ) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 279 of file Block.cpp.

virtual double mvsim::Block::getMass ( ) const [inline, virtual]

Get the block mass

Definition at line 63 of file Block.h.

virtual float mvsim::Block::getMaxBlockRadius ( ) const [inline, virtual]

Get (an approximation of) the max radius of the block, from its point of reference (in meters)

Definition at line 61 of file Block.h.

const std::string& mvsim::Block::getName ( ) const [inline]

User-supplied name of the block (e.g. "block1")

Definition at line 90 of file Block.h.

const mrpt::math::TPose3D& mvsim::Block::getPose ( ) const [inline]

Last time-step pose (of the ref. point, in global coords) (ground-truth)

Definition at line 70 of file Block.h.

const vec3& mvsim::Block::getVelocity ( ) const [inline]

Last time-step velocity (of the ref. point, in global coords) (ground-truth)

Definition at line 84 of file Block.h.

Last time-step velocity (of the ref. point, in local coords) (ground-truth)

Last time-step velocity (of the ref. point, in local coords)

Definition at line 268 of file Block.cpp.

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.

Definition at line 285 of file Block.cpp.

void Block::register_block_class ( const rapidxml::xml_node< char > *  xml_node) [static]

Register a new class of blocks from XML description of type "<block:class name='name'>...</block:class>".

Register a new class of vehicles from XML description of type "<vehicle:class name='name'>...</vehicle:class>".

Definition at line 82 of file Block.cpp.

void mvsim::Block::setBlockIndex ( size_t  idx) [inline]

Set the block index in the World

Definition at line 95 of file Block.h.

void mvsim::Block::setPose ( const mrpt::math::TPose3D &  p) const [inline]

Manually override block pose (Use with caution!) (purposely set as "const")

Definition at line 75 of file Block.h.

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.

Definition at line 266 of file Block.cpp.

Gets the body dynamical state into q, dot{q}

Definition at line 58 of file Block.cpp.

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.

Definition at line 263 of file Block.cpp.


Member Data Documentation

size_t mvsim::Block::m_block_index [protected]

user-supplied index number: must be set/get'ed

Definition at line 108 of file Block.h.

std::string mvsim::Block::m_name [protected]

User-supplied name of the block (e.g. "r1", "veh1")

Definition at line 107 of file Block.h.


The documentation for this class was generated from the following files:


mvsim
Author(s):
autogenerated on Thu Sep 7 2017 09:27:49