Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
mvsim::GroundGrid Class Reference

#include <GroundGrid.h>

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

Public Member Functions

 GroundGrid (World *parent, const rapidxml::xml_node< char > *root)
 
virtual void loadConfigFrom (const rapidxml::xml_node< char > *root) override
 
void poses_mutex_lock () override
 
void poses_mutex_unlock () override
 
virtual ~GroundGrid ()
 
- Public Member Functions inherited from mvsim::WorldElementBase
 WorldElementBase (World *parent)
 
virtual ~WorldElementBase ()
 
- 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
virtual void apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0))
 
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
 
virtual void simul_post_timestep (const TSimulContext &context)
 
virtual void simul_pre_timestep (const TSimulContext &context)
 

Protected Member Functions

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

Protected Attributes

mrpt::img::TColor m_color
 
std::string m_float_center_at_vehicle_name
 
mrpt::opengl::CGridPlaneXY::Ptr m_gl_groundgrid
 
double m_interval
 
bool m_is_floating
 
double m_line_width
 
double m_x_max
 
double m_x_min
 
double m_y_max
 
double m_y_min
 
- 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
 

Additional Inherited Members

- Public Types inherited from mvsim::WorldElementBase
using Ptr = std::shared_ptr< WorldElementBase >
 
- Public Types inherited from mvsim::Simulable
using Ptr = std::shared_ptr< Simulable >
 
- Static Public Member Functions inherited from mvsim::WorldElementBase
static Ptr factory (World *parent, const rapidxml::xml_node< char > *xml_node, const char *class_name=nullptr)
 

Detailed Description

Definition at line 18 of file GroundGrid.h.

Constructor & Destructor Documentation

GroundGrid::GroundGrid ( World parent,
const rapidxml::xml_node< char > *  root 
)

Definition at line 21 of file GroundGrid.cpp.

GroundGrid::~GroundGrid ( )
virtual

Definition at line 37 of file GroundGrid.cpp.

Member Function Documentation

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

Implements mvsim::VisualObject.

Definition at line 62 of file GroundGrid.cpp.

void GroundGrid::loadConfigFrom ( const rapidxml::xml_node< char > *  root)
overridevirtual

Implements mvsim::WorldElementBase.

Definition at line 38 of file GroundGrid.cpp.

void mvsim::GroundGrid::poses_mutex_lock ( )
inlineoverridevirtual

Implements mvsim::Simulable.

Definition at line 26 of file GroundGrid.h.

void mvsim::GroundGrid::poses_mutex_unlock ( )
inlineoverridevirtual

Implements mvsim::Simulable.

Definition at line 27 of file GroundGrid.h.

Member Data Documentation

mrpt::img::TColor mvsim::GroundGrid::m_color
protected

Definition at line 36 of file GroundGrid.h.

std::string mvsim::GroundGrid::m_float_center_at_vehicle_name
protected

Definition at line 34 of file GroundGrid.h.

mrpt::opengl::CGridPlaneXY::Ptr mvsim::GroundGrid::m_gl_groundgrid
protected

Definition at line 39 of file GroundGrid.h.

double mvsim::GroundGrid::m_interval
protected

Definition at line 35 of file GroundGrid.h.

bool mvsim::GroundGrid::m_is_floating
protected

Definition at line 33 of file GroundGrid.h.

double mvsim::GroundGrid::m_line_width
protected

Definition at line 37 of file GroundGrid.h.

double mvsim::GroundGrid::m_x_max
protected

Definition at line 35 of file GroundGrid.h.

double mvsim::GroundGrid::m_x_min
protected

Definition at line 35 of file GroundGrid.h.

double mvsim::GroundGrid::m_y_max
protected

Definition at line 35 of file GroundGrid.h.

double mvsim::GroundGrid::m_y_min
protected

Definition at line 35 of file GroundGrid.h.


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


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