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::TPolygon2D & blockShape () const
 
void blockShape (const mrpt::math::TPolygon2D &p)
 
virtual void create_multibody_system (b2World &world)
 
bool default_block_z_min_max () const
 
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)
 
VisualObjectmeAsVisualObject () 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
const std::optional< Shape2p5 > & collisionShape () const
 
void customVisualVisible (const bool visible)
 
bool customVisualVisible () const
 
virtual void guiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical)
 
Worldparent ()
 
const Worldparent () const
 
void showCollisionShape (bool show)
 
 VisualObject (World *parent, bool insertCustomVizIntoViz=true, bool insertCustomVizIntoPhysical=true)
 
virtual ~VisualObject ()
 
- Public Member Functions inherited from mvsim::Simulable
const b2Bodyb2d_body () const
 
b2Bodyb2d_body ()
 
virtual void freeOpenGLResources ()
 
mrpt::poses::CPose2D getCPose2D () const
 Alternative to getPose() More...
 
mrpt::poses::CPose3D getCPose3D () const
 Alternative to getPose() More...
 
mrpt::math::TVector3D getLinearAcceleration () const
 
const std::string & getName () const
 
mrpt::math::TPose3D getPose () const
 
mrpt::math::TPose3D getPoseNoLock () const
 No thread-safe version. Used internally only. More...
 
WorldgetSimulableWorldObject ()
 
const WorldgetSimulableWorldObject () const
 
mrpt::math::TTwist2D getTwist () 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
 
 Simulable (World *parent)
 

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)
 
- Static Public Member Functions inherited from mvsim::VisualObject
static void FreeOpenGLResources ()
 

Protected Member Functions

virtual void internalGuiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
 
void updateMaxRadiusFromPoly ()
 
- Protected Member Functions inherited from mvsim::VisualObject
void addCustomVisualization (const mrpt::opengl::CRenderizable::Ptr &glModel, const mrpt::poses::CPose3D &modelPose={}, const float modelScale=1.0f, const std::string &modelName="group", const std::optional< std::string > &modelURI=std::nullopt, const bool initialShowBoundingBox=false)
 
bool parseVisual (const rapidxml::xml_node< char > &rootNode)
 Returns true if there is at least one <visual>...</visual> entry. More...
 
bool parseVisual (const JointXMLnode<> &rootNode)
 
void setCollisionShape (const Shape2p5 &cs)
 

Protected Attributes

mrpt::img::TColor block_color_ {0x00, 0x00, 0xff}
 
mrpt::math::TPoint2D block_com_ {.0, .0}
 In local coordinates. More...
 
mrpt::math::TPolygon2D block_poly_
 
double block_z_max_ = std::numeric_limits<double>::quiet_NaN()
 
double block_z_min_ = std::numeric_limits<double>::quiet_NaN()
 
size_t blockIndex_ = 0
 
b2Fixturefixture_block_
 
std::vector< b2FrictionJoint * > friction_joints_
 
double groundFriction_ = 0.5
 Default: 0.5. More...
 
bool intangible_ = false
 
bool isStatic_ = false
 
double lateral_friction_ = 0.5
 Default: 0.5. More...
 
double mass_ = 30.0
 
double maxRadius_
 
const TParameterDefinitions params_
 
double restitution_ = 0.01
 Default: 0.01. More...
 
- Protected Attributes inherited from mvsim::VisualObject
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCollision_
 
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCustomVisual_
 
int32_t glCustomVisualId_ = -1
 
const bool insertCustomVizIntoPhysical_ = true
 
const bool insertCustomVizIntoViz_ = true
 
Worldworld_
 
- Protected Attributes inherited from mvsim::Simulable
std::string name_
 

Private Member Functions

void internal_internalGuiUpdate_forces (mrpt::opengl::COpenGLScene &scene)
 
void internal_parseGeometry (const rapidxml::xml_node< char > &xml_geom_node)
 

Private Attributes

std::vector< mrpt::math::TSegment3D > force_segments_for_rendering_
 
std::mutex force_segments_for_rendering_cs_
 
mrpt::opengl::CSetOfObjects::Ptr gl_block_
 
mrpt::opengl::CSetOfLines::Ptr gl_forces_
 

Additional Inherited Members

- Static Public Attributes inherited from mvsim::VisualObject
static double GeometryEpsilon = 1e-3
 

Detailed Description

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

Definition at line 34 of file Block.h.

Member Typedef Documentation

◆ Ptr

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

Definition at line 37 of file Block.h.

Constructor & Destructor Documentation

◆ Block()

Block::Block ( World parent)

Definition at line 40 of file Block.cpp.

Member Function Documentation

◆ apply_force()

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

◆ block_color() [1/2]

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

Definition at line 99 of file Block.h.

◆ block_color() [2/2]

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

Definition at line 100 of file Block.h.

◆ block_z_max() [1/2]

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

Definition at line 107 of file Block.h.

◆ block_z_max() [2/2]

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

Definition at line 113 of file Block.h.

◆ block_z_min() [1/2]

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

Definition at line 106 of file Block.h.

◆ block_z_min() [2/2]

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

Definition at line 108 of file Block.h.

◆ blockShape() [1/2]

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 74 of file Block.h.

◆ blockShape() [2/2]

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

Definition at line 76 of file Block.h.

◆ create_multibody_system()

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

◆ default_block_z_min_max()

bool Block::default_block_z_min_max ( ) const

returns true if none of the min/max block z limits has been set explicitly yet. Used while parsing the shape_from_visual tag.

Definition at line 541 of file Block.cpp.

◆ factory() [1/2]

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

◆ factory() [2/2]

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

◆ getBlockCenterOfMass()

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

In local coordinates.

Definition at line 67 of file Block.h.

◆ getBlockIndex()

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

Get the block index in the World

Definition at line 86 of file Block.h.

◆ getBox2DBlockBody()

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

Definition at line 66 of file Block.h.

◆ getMass()

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

Get the block mass

Definition at line 65 of file Block.h.

◆ getMaxBlockRadius()

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 63 of file Block.h.

◆ ground_friction() [1/2]

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

Definition at line 90 of file Block.h.

◆ ground_friction() [2/2]

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

Definition at line 91 of file Block.h.

◆ internal_internalGuiUpdate_forces()

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

Definition at line 303 of file Block.cpp.

◆ internal_parseGeometry()

void Block::internal_parseGeometry ( const rapidxml::xml_node< char > &  xml_geom_node)
private

Definition at line 467 of file Block.cpp.

◆ internalGuiUpdate()

void Block::internalGuiUpdate ( const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &  viz,
const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &  physical,
bool  childrenOnly 
)
overrideprotectedvirtual

Implements mvsim::VisualObject.

Definition at line 249 of file Block.cpp.

◆ isStatic()

bool Block::isStatic ( ) const

Definition at line 437 of file Block.cpp.

◆ mass() [1/2]

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

Definition at line 93 of file Block.h.

◆ mass() [2/2]

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

Definition at line 94 of file Block.h.

◆ meAsVisualObject()

VisualObject* mvsim::Block::meAsVisualObject ( )
inlineoverridevirtual

Reimplemented from mvsim::Simulable.

Definition at line 123 of file Block.h.

◆ register_block_class()

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

◆ setBlockIndex()

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

Set the block index in the World

Definition at line 84 of file Block.h.

◆ setIsStatic()

void Block::setIsStatic ( bool  b)

Definition at line 444 of file Block.cpp.

◆ simul_post_timestep()

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

◆ simul_pre_timestep()

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

◆ updateMaxRadiusFromPoly()

void Block::updateMaxRadiusFromPoly ( )
protected

Definition at line 319 of file Block.cpp.

Member Data Documentation

◆ block_color_

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

Definition at line 149 of file Block.h.

◆ block_com_

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

In local coordinates.

Definition at line 150 of file Block.h.

◆ block_poly_

mrpt::math::TPolygon2D mvsim::Block::block_poly_
protected

Definition at line 140 of file Block.h.

◆ block_z_max_

double mvsim::Block::block_z_max_ = std::numeric_limits<double>::quiet_NaN()
protected

Definition at line 147 of file Block.h.

◆ block_z_min_

double mvsim::Block::block_z_min_ = std::numeric_limits<double>::quiet_NaN()
protected

Definition at line 146 of file Block.h.

◆ blockIndex_

size_t mvsim::Block::blockIndex_ = 0
protected

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

Definition at line 133 of file Block.h.

◆ fixture_block_

b2Fixture* mvsim::Block::fixture_block_
protected

Definition at line 176 of file Block.h.

◆ force_segments_for_rendering_

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

Definition at line 186 of file Block.h.

◆ force_segments_for_rendering_cs_

std::mutex mvsim::Block::force_segments_for_rendering_cs_
private

Definition at line 185 of file Block.h.

◆ friction_joints_

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

Definition at line 135 of file Block.h.

◆ gl_block_

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

Definition at line 183 of file Block.h.

◆ gl_forces_

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

Definition at line 184 of file Block.h.

◆ groundFriction_

double mvsim::Block::groundFriction_ = 0.5
protected

Default: 0.5.

Definition at line 153 of file Block.h.

◆ intangible_

bool mvsim::Block::intangible_ = false
protected

If intangible, a block will be rendered visually but will be neither detected by sensors, nor collide

Definition at line 158 of file Block.h.

◆ isStatic_

bool mvsim::Block::isStatic_ = false
protected

Definition at line 139 of file Block.h.

◆ lateral_friction_

double mvsim::Block::lateral_friction_ = 0.5
protected

Default: 0.5.

Definition at line 152 of file Block.h.

◆ mass_

double mvsim::Block::mass_ = 30.0
protected

Definition at line 138 of file Block.h.

◆ maxRadius_

double mvsim::Block::maxRadius_
protected

Automatically computed from block_poly_ upon each change via updateMaxRadiusFromPoly()

Definition at line 144 of file Block.h.

◆ params_

const TParameterDefinitions mvsim::Block::params_
protected
Initial value:
= {
{"mass", {"%lf", &mass_}},
{"zmin", {"%lf", &block_z_min_}},
{"zmax", {"%lf", &block_z_max_}},
{"ground_friction", {"%lf", &groundFriction_}},
{"lateral_friction", {"%lf", &lateral_friction_}},
{"restitution", {"%lf", &restitution_}},
{"color", {"%color", &block_color_}},
{"intangible", {"%bool", &intangible_}},
{"static", {"%bool", &isStatic_}}
}

Definition at line 160 of file Block.h.

◆ restitution_

double mvsim::Block::restitution_ = 0.01
protected

Default: 0.01.

Definition at line 154 of file Block.h.


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


mvsim
Author(s):
autogenerated on Tue Jul 4 2023 03:08:23