Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
mvsim::Block Class Reference

#include <Block.h>

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

Public Types

using Ptr = std::shared_ptr< Block >
 
- Public Types inherited from mvsim::Simulable
using Ptr = std::shared_ptr< Simulable >
 

Public Member Functions

virtual void apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) override
 
 Block (World *parent)
 
const mrpt::img::TColor block_color () const
 
void block_color (const mrpt::img::TColor &c)
 
double block_z_max () const
 
void block_z_max (double v)
 
double block_z_min () const
 
void block_z_min (double v)
 
const mrpt::math::TPolygon2DblockShape () const
 
void blockShape (const mrpt::math::TPolygon2D &p)
 
virtual void create_multibody_system (b2World &world)
 
mrpt::math::TPoint2D getBlockCenterOfMass () const
 In local coordinates. More...
 
size_t getBlockIndex () const
 
b2BodygetBox2DBlockBody ()
 
virtual double getMass () const
 
virtual float getMaxBlockRadius () const
 
double ground_friction () const
 
void ground_friction (double newValue)
 
bool isStatic () const
 
double mass () const
 
void mass (double newValue)
 
void poses_mutex_lock () override
 
void poses_mutex_unlock () override
 
void setBlockIndex (size_t idx)
 
void setIsStatic (bool b)
 
virtual void simul_post_timestep (const TSimulContext &context) override
 
virtual void simul_pre_timestep (const TSimulContext &context) override
 
- Public Member Functions inherited from mvsim::VisualObject
void getVisualModelBoundingBox (mrpt::math::TPoint3D &bbmin, mrpt::math::TPoint3D &bbmax) const
 
WorldgetWorldObject ()
 
const WorldgetWorldObject () const
 
virtual void guiUpdate (mrpt::opengl::COpenGLScene &scene)
 
void showBoundingBox (bool show)
 
 VisualObject (World *parent)
 
virtual ~VisualObject ()
 
- Public Member Functions inherited from mvsim::Simulable
const b2Bodyb2d_body () const
 
b2Bodyb2d_body ()
 
mrpt::poses::CPose2D getCPose2D () const
 Alternative to getPose() More...
 
const std::stringgetName () const
 
mrpt::math::TPose3D getPose () const
 
mrpt::math::TTwist2D getTwist () const
 
const mrpt::math::TTwist2DgetVelocity () const
 
mrpt::math::TTwist2D getVelocityLocal () const
 
bool hadCollision () const
 
bool isInCollision () const
 
virtual void registerOnServer (mvsim::Client &c)
 
void resetCollisionFlag ()
 
void setName (const std::string &s)
 
void setPose (const mrpt::math::TPose3D &p) const
 
void setTwist (const mrpt::math::TTwist2D &dq) const
 

Static Public Member Functions

static Ptr factory (World *parent, const rapidxml::xml_node< char > *xml_node)
 
static Ptr factory (World *parent, const std::string &xml_text)
 
static void register_block_class (const rapidxml::xml_node< char > *xml_node)
 

Protected Member Functions

virtual mrpt::poses::CPose3D internalGuiGetVisualPose () override
 
virtual void internalGuiUpdate (mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override
 
void updateMaxRadiusFromPoly ()
 
- Protected Member Functions inherited from mvsim::VisualObject
bool parseVisual (const rapidxml::xml_node< char > *visual_node)
 

Protected Attributes

mrpt::img::TColor m_block_color {0x00, 0x00, 0xff}
 
mrpt::math::TPoint2D m_block_com {.0, .0}
 In local coordinates. More...
 
size_t m_block_index = 0
 
mrpt::math::TPolygon2D m_block_poly
 
double m_block_z_max = 1.0
 
double m_block_z_min = 0.0
 each change via updateMaxRadiusFromPoly() More...
 
b2Fixturem_fixture_block
 
std::vector< b2FrictionJoint * > m_friction_joints
 
double m_ground_friction = 0.5
 Default: 0.5. More...
 
bool m_isStatic = false
 
double m_lateral_friction = 0.5
 Default: 0.5. More...
 
double m_mass = 30.0
 
double m_max_radius
 
const TParameterDefinitions m_params
 
double m_restitution = 0.01
 Deault: 0.01. More...
 
- Protected Attributes inherited from mvsim::VisualObject
std::shared_ptr< mrpt::opengl::CSetOfObjectsm_glBoundingBox
 
std::shared_ptr< mrpt::opengl::CSetOfObjectsm_glCustomVisual
 
int32_t m_glCustomVisualId = -1
 
Worldm_world
 
- Protected Attributes inherited from mvsim::Simulable
std::string m_name
 

Private Member Functions

void internal_internalGuiUpdate_forces (mrpt::opengl::COpenGLScene &scene)
 

Private Attributes

std::vector< mrpt::math::TSegment3Dm_force_segments_for_rendering
 
std::mutex m_force_segments_for_rendering_cs
 
mrpt::opengl::CSetOfObjects::Ptr m_gl_block
 
mrpt::opengl::CSetOfLines::Ptr m_gl_forces
 
std::mutex m_gui_mtx
 

Detailed Description

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

Definition at line 33 of file Block.h.

Member Typedef Documentation

using mvsim::Block::Ptr = std::shared_ptr<Block>

Definition at line 36 of file Block.h.

Constructor & Destructor Documentation

Block::Block ( World parent)

Definition at line 36 of file Block.cpp.

Member Function Documentation

void Block::apply_force ( const mrpt::math::TVector2D &  force,
const mrpt::math::TPoint2D applyPoint = mrpt::math::TPoint2D(0, 0) 
)
overridevirtual

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 408 of file Block.cpp.

const mrpt::img::TColor mvsim::Block::block_color ( ) const
inline

Definition at line 101 of file Block.h.

void mvsim::Block::block_color ( const mrpt::img::TColor &  c)
inline

Definition at line 102 of file Block.h.

double mvsim::Block::block_z_max ( ) const
inline

Definition at line 109 of file Block.h.

void mvsim::Block::block_z_max ( double  v)
inline

Definition at line 115 of file Block.h.

double mvsim::Block::block_z_min ( ) const
inline

Definition at line 108 of file Block.h.

void mvsim::Block::block_z_min ( double  v)
inline

Definition at line 110 of file Block.h.

const mrpt::math::TPolygon2D& mvsim::Block::blockShape ( ) const
inline

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

Definition at line 73 of file Block.h.

void mvsim::Block::blockShape ( const mrpt::math::TPolygon2D p)
inline

Definition at line 75 of file Block.h.

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 329 of file Block.cpp.

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

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

Definition at line 68 of file Block.cpp.

Block::Ptr 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 220 of file Block.cpp.

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

In local coordinates.

Definition at line 66 of file Block.h.

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

Get the block index in the World

Definition at line 85 of file Block.h.

b2Body* mvsim::Block::getBox2DBlockBody ( )
inline

Definition at line 65 of file Block.h.

virtual double mvsim::Block::getMass ( ) const
inlinevirtual

Get the block mass

Definition at line 64 of file Block.h.

virtual float mvsim::Block::getMaxBlockRadius ( ) const
inlinevirtual

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

Definition at line 62 of file Block.h.

double mvsim::Block::ground_friction ( ) const
inline

Definition at line 89 of file Block.h.

void mvsim::Block::ground_friction ( double  newValue)
inline

Definition at line 90 of file Block.h.

void Block::internal_internalGuiUpdate_forces ( mrpt::opengl::COpenGLScene scene)
private

Definition at line 301 of file Block.cpp.

mrpt::poses::CPose3D Block::internalGuiGetVisualPose ( )
overrideprotectedvirtual

Reimplemented from mvsim::VisualObject.

Definition at line 255 of file Block.cpp.

void Block::internalGuiUpdate ( mrpt::opengl::COpenGLScene scene,
bool  childrenOnly 
)
overrideprotectedvirtual

Implements mvsim::VisualObject.

Definition at line 260 of file Block.cpp.

bool Block::isStatic ( ) const

Definition at line 418 of file Block.cpp.

double mvsim::Block::mass ( ) const
inline

Definition at line 92 of file Block.h.

void mvsim::Block::mass ( double  newValue)
inline

Definition at line 93 of file Block.h.

void mvsim::Block::poses_mutex_lock ( )
inlineoverridevirtual

Implements mvsim::Simulable.

Definition at line 98 of file Block.h.

void mvsim::Block::poses_mutex_unlock ( )
inlineoverridevirtual

Implements mvsim::Simulable.

Definition at line 99 of file Block.h.

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 48 of file Block.cpp.

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

Set the block index in the World

Definition at line 83 of file Block.h.

void Block::setIsStatic ( bool  b)

Definition at line 424 of file Block.cpp.

void Block::simul_post_timestep ( const TSimulContext context)
overridevirtual

Override to do any required process right after the integration of dynamic equations for each timestep

Reimplemented from mvsim::Simulable.

Definition at line 250 of file Block.cpp.

void Block::simul_pre_timestep ( const TSimulContext context)
overridevirtual

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 243 of file Block.cpp.

void Block::updateMaxRadiusFromPoly ( )
protected

Definition at line 316 of file Block.cpp.

Member Data Documentation

mrpt::img::TColor mvsim::Block::m_block_color {0x00, 0x00, 0xff}
protected

Definition at line 139 of file Block.h.

mrpt::math::TPoint2D mvsim::Block::m_block_com {.0, .0}
protected

In local coordinates.

Definition at line 140 of file Block.h.

size_t mvsim::Block::m_block_index = 0
protected

user-supplied index number: must be set/get'ed with setblockIndex() getblockIndex() (default=0)

Definition at line 128 of file Block.h.

mrpt::math::TPolygon2D mvsim::Block::m_block_poly
protected

Definition at line 135 of file Block.h.

double mvsim::Block::m_block_z_max = 1.0
protected

Definition at line 138 of file Block.h.

double mvsim::Block::m_block_z_min = 0.0
protected

each change via updateMaxRadiusFromPoly()

Definition at line 138 of file Block.h.

b2Fixture* mvsim::Block::m_fixture_block
protected

Definition at line 158 of file Block.h.

std::vector<mrpt::math::TSegment3D> mvsim::Block::m_force_segments_for_rendering
private

Definition at line 166 of file Block.h.

std::mutex mvsim::Block::m_force_segments_for_rendering_cs
private

Definition at line 165 of file Block.h.

std::vector<b2FrictionJoint*> mvsim::Block::m_friction_joints
protected

Definition at line 130 of file Block.h.

mrpt::opengl::CSetOfObjects::Ptr mvsim::Block::m_gl_block
private

Definition at line 163 of file Block.h.

mrpt::opengl::CSetOfLines::Ptr mvsim::Block::m_gl_forces
private

Definition at line 164 of file Block.h.

double mvsim::Block::m_ground_friction = 0.5
protected

Default: 0.5.

Definition at line 143 of file Block.h.

std::mutex mvsim::Block::m_gui_mtx
private

Definition at line 168 of file Block.h.

bool mvsim::Block::m_isStatic = false
protected

Definition at line 134 of file Block.h.

double mvsim::Block::m_lateral_friction = 0.5
protected

Default: 0.5.

Definition at line 142 of file Block.h.

double mvsim::Block::m_mass = 30.0
protected

Definition at line 133 of file Block.h.

double mvsim::Block::m_max_radius
protected

Automatically computed from m_block_poly upon

Definition at line 136 of file Block.h.

const TParameterDefinitions mvsim::Block::m_params
protected
Initial value:
= {
{"mass", {"%lf", &m_mass}},
{"zmin", {"%lf", &m_block_z_min}},
{"zmax", {"%lf", &m_block_z_max}},
{"ground_friction", {"%lf", &m_ground_friction}},
{"lateral_friction", {"%lf", &m_lateral_friction}},
{"restitution", {"%lf", &m_restitution}},
{"color", {"%color", &m_block_color}}}

Definition at line 146 of file Block.h.

double mvsim::Block::m_restitution = 0.01
protected

Deault: 0.01.

Definition at line 144 of file Block.h.


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


mvsim
Author(s):
autogenerated on Fri May 7 2021 03:05:52