Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
mvsim::SensorBase Class Referenceabstract

#include <SensorBase.h>

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

Public Types

using Ptr = std::shared_ptr< SensorBase >
 
- Public Types inherited from mvsim::Simulable
using Ptr = std::shared_ptr< Simulable >
 

Public Member Functions

virtual void loadConfigFrom (const rapidxml::xml_node< char > *root)=0
 
void registerOnServer (mvsim::Client &c) override
 (in seconds) (Default = 0.1) More...
 
 SensorBase (VehicleBase &vehicle)
 
virtual ~SensorBase ()
 which the sensor is attached. More...
 
- 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 poses_mutex_lock ()=0
 
virtual void poses_mutex_unlock ()=0
 
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)
 

Static Public Member Functions

static SensorBase::Ptr factory (VehicleBase &parent, const rapidxml::xml_node< char > *xml_node)
 

Public Attributes

double m_sensor_period
 

Protected Member Functions

bool parseSensorPublish (const rapidxml::xml_node< char > *node, const std::map< std::string, std::string > &varValues)
 
void reportNewObservation (const std::shared_ptr< mrpt::obs::CObservation > &obs, const TSimulContext &context)
 
- Protected Member Functions inherited from mvsim::VisualObject
virtual mrpt::poses::CPose3D internalGuiGetVisualPose ()
 
virtual void internalGuiUpdate (mrpt::opengl::COpenGLScene &scene, bool childrenOnly=false)=0
 
bool parseVisual (const rapidxml::xml_node< char > *visual_node)
 

Protected Attributes

double m_sensor_last_timestamp
 
VehicleBasem_vehicle
 The vehicle this sensor is attached to. More...
 
std::string publishTopic_
 
- 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
 

Detailed Description

Definition at line 21 of file SensorBase.h.

Member Typedef Documentation

using mvsim::SensorBase::Ptr = std::shared_ptr<SensorBase>

Definition at line 24 of file SensorBase.h.

Constructor & Destructor Documentation

SensorBase::SensorBase ( VehicleBase vehicle)

Ctor takes a ref to the vehicle to

Definition at line 44 of file SensorBase.cpp.

SensorBase::~SensorBase ( )
virtualdefault

which the sensor is attached.

Member Function Documentation

SensorBase::Ptr SensorBase::factory ( VehicleBase parent,
const rapidxml::xml_node< char > *  xml_node 
)
static

Class factory: Creates a sensor from XML description of type "<sensor class='CLASS_NAME'>...</sensor>".

Definition at line 54 of file SensorBase.cpp.

virtual void mvsim::SensorBase::loadConfigFrom ( const rapidxml::xml_node< char > *  root)
pure virtual

Implemented in mvsim::LaserScanner.

bool SensorBase::parseSensorPublish ( const rapidxml::xml_node< char > *  node,
const std::map< std::string, std::string > &  varValues 
)
protected

Definition at line 88 of file SensorBase.cpp.

void SensorBase::registerOnServer ( mvsim::Client c)
overridevirtual

(in seconds) (Default = 0.1)

Reimplemented from mvsim::Simulable.

Definition at line 132 of file SensorBase.cpp.

void SensorBase::reportNewObservation ( const std::shared_ptr< mrpt::obs::CObservation > &  obs,
const TSimulContext context 
)
protected

Definition at line 106 of file SensorBase.cpp.

Member Data Documentation

double mvsim::SensorBase::m_sensor_last_timestamp
protected

The last sensor reading timestamp. See m_sensor_period

Definition at line 46 of file SensorBase.h.

double mvsim::SensorBase::m_sensor_period

Generate one sensor reading every this period

Definition at line 37 of file SensorBase.h.

VehicleBase& mvsim::SensorBase::m_vehicle
protected

The vehicle this sensor is attached to.

Definition at line 43 of file SensorBase.h.

std::string mvsim::SensorBase::publishTopic_
protected

Definition at line 48 of file SensorBase.h.


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


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