#include <OccupancyGridMap.h>
Classes | |
struct | TFixturePtr |
struct | TInfoPerCollidableobj |
Public Member Functions | |
void | doLoadConfigFrom (const rapidxml::xml_node< char > *root) |
const mrpt::maps::COccupancyGridMap2D & | getOccGrid () const |
mrpt::maps::COccupancyGridMap2D & | getOccGrid () |
virtual void | loadConfigFrom (const rapidxml::xml_node< char > *root) override |
OccupancyGridMap (World *parent, const rapidxml::xml_node< char > *root) | |
virtual void | simul_pre_timestep (const TSimulContext &context) override |
virtual | ~OccupancyGridMap () |
![]() | |
WorldElementBase (World *parent) | |
virtual | ~WorldElementBase () |
![]() | |
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 () |
![]() | |
virtual void | apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) |
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 VisualObject * | meAsVisualObject () |
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 |
virtual void | simul_post_timestep (const TSimulContext &context) |
Simulable (World *parent) | |
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 | 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::opengl::CSetOfObjects::Ptr | gl_grid_ |
call of internalGuiUpdate() More... | |
std::vector< mrpt::opengl::CSetOfObjects::Ptr > | gl_obs_clouds_ |
std::vector< mrpt::opengl::CPointCloud::Ptr > | gl_obs_clouds_buffer_ |
std::mutex | gl_obs_clouds_buffer_cs_ |
mrpt::maps::COccupancyGridMap2D | grid_ |
bool | gui_uptodate_ |
double | lateral_friction_ |
(Default: 0.5) More... | |
std::vector< TInfoPerCollidableobj > | obstacles_for_each_obj_ |
double | restitution_ |
Elastic restitution coef (default: 0.01) More... | |
bool | show_grid_collision_points_ |
mrpt::obs::CSinCosLookUpTableFor2DScans | sincos_lut_ |
![]() | |
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_ |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< WorldElementBase > |
![]() | |
using | Ptr = std::shared_ptr< Simulable > |
![]() | |
static Ptr | factory (World *parent, const rapidxml::xml_node< char > *xml_node, const char *class_name=nullptr) |
![]() | |
static void | FreeOpenGLResources () |
![]() | |
static double | GeometryEpsilon = 1e-3 |
Definition at line 24 of file OccupancyGridMap.h.
OccupancyGridMap::OccupancyGridMap | ( | World * | parent, |
const rapidxml::xml_node< char > * | root | ||
) |
Definition at line 28 of file OccupancyGridMap.cpp.
|
virtual |
Definition at line 39 of file OccupancyGridMap.cpp.
void OccupancyGridMap::doLoadConfigFrom | ( | const rapidxml::xml_node< char > * | root | ) |
Definition at line 41 of file OccupancyGridMap.cpp.
|
inline |
Definition at line 40 of file OccupancyGridMap.h.
|
inline |
Definition at line 41 of file OccupancyGridMap.h.
|
overrideprotectedvirtual |
Implements mvsim::VisualObject.
Definition at line 107 of file OccupancyGridMap.cpp.
|
inlineoverridevirtual |
Implements mvsim::WorldElementBase.
Definition at line 33 of file OccupancyGridMap.h.
|
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 167 of file OccupancyGridMap.cpp.
|
protected |
call of internalGuiUpdate()
Definition at line 53 of file OccupancyGridMap.h.
|
protected |
Definition at line 73 of file OccupancyGridMap.h.
|
protected |
Definition at line 76 of file OccupancyGridMap.h.
|
protected |
Definition at line 75 of file OccupancyGridMap.h.
|
protected |
Definition at line 49 of file OccupancyGridMap.h.
|
protected |
Whether gl_grid_ has to be updated upon next
Definition at line 51 of file OccupancyGridMap.h.
|
protected |
(Default: 0.5)
Definition at line 82 of file OccupancyGridMap.h.
|
protected |
Definition at line 72 of file OccupancyGridMap.h.
|
protected |
Elastic restitution coef (default: 0.01)
Definition at line 81 of file OccupancyGridMap.h.
|
protected |
Definition at line 80 of file OccupancyGridMap.h.
|
protected |
Definition at line 78 of file OccupancyGridMap.h.