#include <Block.h>
Public Types | |
using | Ptr = std::shared_ptr< Block > |
![]() | |
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 |
b2Body * | getBox2DBlockBody () |
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) |
VisualObject * | meAsVisualObject () 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 |
![]() | |
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) |
World * | parent () |
const World * | parent () const |
void | showCollisionShape (bool show) |
VisualObject (World *parent, bool insertCustomVizIntoViz=true, bool insertCustomVizIntoPhysical=true) | |
virtual | ~VisualObject () |
![]() | |
const b2Body * | b2d_body () const |
b2Body * | b2d_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... | |
World * | getSimulableWorldObject () |
const World * | getSimulableWorldObject () 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 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 () |
![]() | |
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 |
b2Fixture * | fixture_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... | |
![]() | |
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 |
World * | world_ |
![]() | |
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 double | GeometryEpsilon = 1e-3 |
A non-vehicle "actor" for the simulation, typically obstacle blocks.
using mvsim::Block::Ptr = std::shared_ptr<Block> |
|
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.
|
inline |
|
inline |
|
inline |
|
inline |
bool Block::default_block_z_min_max | ( | ) | const |
|
static |
|
static |
|
inline |
|
inline |
|
inlinevirtual |
|
inlinevirtual |
|
private |
|
private |
|
overrideprotectedvirtual |
Implements mvsim::VisualObject.
|
inlineoverridevirtual |
Reimplemented from mvsim::Simulable.
|
static |
|
inline |
|
overridevirtual |
Override to do any required process right after the integration of dynamic equations for each timestep
Reimplemented from mvsim::Simulable.
|
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.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
private |
|
private |
|
protected |
|
private |
|
private |
|
protected |
|
protected |
|
protected |
|
protected |
Automatically computed from block_poly_ upon each change via updateMaxRadiusFromPoly()
|
protected |
|
protected |