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

#include <ElevationMap.h>

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

Public Member Functions

 ElevationMap (World *parent, const rapidxml::xml_node< char > *root)
 
std::optional< float > getElevationAt (const mrpt::math::TPoint2D &pt) const override
 
virtual void loadConfigFrom (const rapidxml::xml_node< char > *root) override
 
virtual void simul_post_timestep (const TSimulContext &context) override
 
virtual void simul_pre_timestep (const TSimulContext &context) override
 
virtual ~ElevationMap ()
 
- Public Member Functions inherited from mvsim::WorldElementBase
 WorldElementBase (World *parent)
 
virtual ~WorldElementBase ()
 
- Public Member Functions inherited from mvsim::VisualObject
const std::optional< Shape2p5 > & collisionShape () const
 
bool customVisualVisible () const
 
void customVisualVisible (const bool visible)
 
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
virtual void apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0))
 
b2Bodyb2d_body ()
 
const b2Bodyb2d_body () const
 
virtual void freeOpenGLResources ()
 
mrpt::poses::CPose2D getCPose2D () const
 Alternative to getPose() More...
 
mrpt::poses::CPose3D getCPose3D () const
 Alternative to getPose() More...
 
virtual std::optional< float > getElevationAt ([[maybe_unused]] const mrpt::math::TPoint2D &worldXY) const
 
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...
 
virtual mrpt::math::TPose3D getRelativePose () const
 
WorldgetSimulableWorldObject ()
 
const WorldgetSimulableWorldObject () const
 
mrpt::math::TTwist2D getTwist () const
 
mrpt::math::TTwist2D getVelocityLocal () const
 
bool hadCollision () const
 
bool isInCollision () const
 
virtual VisualObjectmeAsVisualObject ()
 
virtual void registerOnServer (mvsim::Client &c)
 
void resetCollisionFlag ()
 
void setName (const std::string &s)
 
void setPose (const mrpt::math::TPose3D &p, bool notifyChange=true) const
 
virtual void setRelativePose (const mrpt::math::TPose3D &p)
 
void setTwist (const mrpt::math::TTwist2D &dq) const
 
 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
 
- 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 JointXMLnode<> &rootNode)
 
bool parseVisual (const rapidxml::xml_node< char > &rootNode)
 Returns true if there is at least one <visual>...</visual> entry. More...
 
void setCollisionShape (const Shape2p5 &cs)
 

Protected Attributes

bool firstSceneRendering_ = true
 
std::vector< mrpt::opengl::CMesh::Ptr > gl_meshes_
 
mrpt::math::CMatrixDouble meshCacheZ_
 
double meshMaxX_ = 0
 
double meshMaxY_ = 0
 
double meshMinX_ = 0
 
double meshMinY_ = 0
 
double model_split_size_ = .0f
 
double resolution_ = 1.0f
 
double textureExtensionX_ = 0
 0=auto More...
 
double textureExtensionY_ = 0
 0=auto 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_
 

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)
 
- Static Public Member Functions inherited from mvsim::VisualObject
static void FreeOpenGLResources ()
 
- Static Public Attributes inherited from mvsim::VisualObject
static double GeometryEpsilon = 1e-3
 

Detailed Description

Simulates a Digital Elevation Model (DEM) for a given terrain.

Input data can be given from a fixed elevation matrix from the XML file, an external image, etc. Refer to examples under mvsim_tutorials.

Definition at line 27 of file ElevationMap.h.

Constructor & Destructor Documentation

◆ ElevationMap()

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

Definition at line 76 of file ElevationMap.cpp.

◆ ~ElevationMap()

ElevationMap::~ElevationMap ( )
virtual

Definition at line 82 of file ElevationMap.cpp.

Member Function Documentation

◆ getElevationAt()

std::optional< float > ElevationMap::getElevationAt ( const mrpt::math::TPoint2D &  pt) const
override

Definition at line 466 of file ElevationMap.cpp.

◆ internalGuiUpdate()

void ElevationMap::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 408 of file ElevationMap.cpp.

◆ loadConfigFrom()

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

Implements mvsim::WorldElementBase.

Definition at line 83 of file ElevationMap.cpp.

◆ simul_post_timestep()

void ElevationMap::simul_post_timestep ( const TSimulContext context)
overridevirtual

Override to do any required process right after the integration of dynamic equations for each timestep. IMPORTANT: Reimplementations MUST also call this base method, since it is in charge of important tasks (e.g. update q_, dq_)

Reimplemented from mvsim::Simulable.

Definition at line 439 of file ElevationMap.cpp.

◆ simul_pre_timestep()

void ElevationMap::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 432 of file ElevationMap.cpp.

Member Data Documentation

◆ firstSceneRendering_

bool mvsim::ElevationMap::firstSceneRendering_ = true
protected

Definition at line 49 of file ElevationMap.h.

◆ gl_meshes_

std::vector<mrpt::opengl::CMesh::Ptr> mvsim::ElevationMap::gl_meshes_
protected

This object holds both, the mesh data, and is in charge of 3D rendering.

Definition at line 48 of file ElevationMap.h.

◆ meshCacheZ_

mrpt::math::CMatrixDouble mvsim::ElevationMap::meshCacheZ_
protected

A copy of elevation data in gl_mesh_. Coordinate order is (x,y)

Definition at line 56 of file ElevationMap.h.

◆ meshMaxX_

double mvsim::ElevationMap::meshMaxX_ = 0
protected

Definition at line 57 of file ElevationMap.h.

◆ meshMaxY_

double mvsim::ElevationMap::meshMaxY_ = 0
protected

Definition at line 57 of file ElevationMap.h.

◆ meshMinX_

double mvsim::ElevationMap::meshMinX_ = 0
protected

Definition at line 57 of file ElevationMap.h.

◆ meshMinY_

double mvsim::ElevationMap::meshMinY_ = 0
protected

Definition at line 57 of file ElevationMap.h.

◆ model_split_size_

double mvsim::ElevationMap::model_split_size_ = .0f
protected

If enabled (>0), the mesh will be split into NxM smaller meshes with a max size of this value, to help correctly render semitransparent objects (e.g. trees).

Definition at line 61 of file ElevationMap.h.

◆ resolution_

double mvsim::ElevationMap::resolution_ = 1.0f
protected

Definition at line 50 of file ElevationMap.h.

◆ textureExtensionX_

double mvsim::ElevationMap::textureExtensionX_ = 0
protected

0=auto

Definition at line 52 of file ElevationMap.h.

◆ textureExtensionY_

double mvsim::ElevationMap::textureExtensionY_ = 0
protected

0=auto

Definition at line 53 of file ElevationMap.h.


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


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:09