#include <Block.h>
Public Types | |
using | Ptr = std::shared_ptr< Block > |
Public Types inherited from mvsim::Simulable | |
using | Ptr = std::shared_ptr< Simulable > |
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... | |
b2Fixture * | m_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::CSetOfObjects > | m_glBoundingBox |
std::shared_ptr< mrpt::opengl::CSetOfObjects > | m_glCustomVisual |
int32_t | m_glCustomVisualId = -1 |
World * | m_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::TSegment3D > | m_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 |
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 |
|
static |
|
static |
|
inline |
|
inline |
|
inlinevirtual |
|
inlinevirtual |
|
private |
|
overrideprotectedvirtual |
Reimplemented from mvsim::VisualObject.
|
overrideprotectedvirtual |
Implements mvsim::VisualObject.
|
inlineoverridevirtual |
Implements mvsim::Simulable.
|
inlineoverridevirtual |
Implements 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 |
each change via updateMaxRadiusFromPoly()
|
private |
|
private |
|
protected |
|
private |
|
private |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |