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

#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)
 
void registerOnServer (mvsim::Client &c) override
 
double sensor_period () const
 
 SensorBase (Simulable &vehicle)
 
virtual void simulateOn3DScene ([[maybe_unused]] mrpt::opengl::COpenGLScene &gl_scene)
 
virtual ~SensorBase ()
 
- Public Member Functions inherited from mvsim::VisualObject
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)
 
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))
 
const b2Bodyb2d_body () const
 
b2Bodyb2d_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...
 
WorldgetSimulableWorldObject ()
 
const WorldgetSimulableWorldObject () const
 
mrpt::math::TTwist2D getTwist () const
 
mrpt::math::TTwist2D getVelocityLocal () const
 
bool hadCollision () const
 
bool isInCollision () const
 
virtual VisualObjectmeAsVisualObject ()
 
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)
 
 Simulable (World *parent)
 

Static Public Member Functions

static SensorBase::Ptr factory (Simulable &parent, const rapidxml::xml_node< char > *xml_node)
 
static std::shared_ptr< mrpt::opengl::CSetOfObjects > GetAllSensorsFOVViz ()
 
static std::shared_ptr< mrpt::opengl::CSetOfObjects > GetAllSensorsOriginViz ()
 
static void RegisterSensorFOVViz (const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
 
static void RegisterSensorOriginViz (const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
 
- Static Public Member Functions inherited from mvsim::VisualObject
static void FreeOpenGLResources ()
 

Protected Member Functions

void make_sure_we_have_a_name (const std::string &prefix)
 Assign a sensible default name/sensor label if none is provided: More...
 
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)
 
void reportNewObservation_lidar_2d (const std::shared_ptr< mrpt::obs::CObservation2DRangeScan > &obs, const TSimulContext &context)
 
bool should_simulate_sensor (const TSimulContext &context)
 
Worldworld ()
 
const Worldworld () const
 
- 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)
 
virtual void internalGuiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly=false)=0
 
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

std::string publishTopic_
 
std::shared_ptr< mrpt::io::CFileGZOutputStream > rawlog_io_
 
std::string save_to_rawlog_
 
double sensor_last_timestamp_ = 0
 
double sensor_period_ = 0.1
 
std::map< std::string, std::string > varValues_
 Filled in by SensorBase::loadConfigFrom() More...
 
Simulablevehicle_
 The vehicle this sensor is attached to. 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

- Static Public Attributes inherited from mvsim::VisualObject
static double GeometryEpsilon = 1e-3
 

Detailed Description

Definition at line 26 of file SensorBase.h.

Member Typedef Documentation

◆ Ptr

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

Definition at line 29 of file SensorBase.h.

Constructor & Destructor Documentation

◆ SensorBase()

SensorBase::SensorBase ( Simulable vehicle)

Ctor takes a ref to the vehicle to which the sensor is attached.

Definition at line 83 of file SensorBase.cpp.

◆ ~SensorBase()

SensorBase::~SensorBase ( )
virtualdefault

Member Function Documentation

◆ factory()

SensorBase::Ptr SensorBase::factory ( Simulable 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 92 of file SensorBase.cpp.

◆ GetAllSensorsFOVViz()

mrpt::opengl::CSetOfObjects::Ptr SensorBase::GetAllSensorsFOVViz ( )
static

Definition at line 65 of file SensorBase.cpp.

◆ GetAllSensorsOriginViz()

mrpt::opengl::CSetOfObjects::Ptr SensorBase::GetAllSensorsOriginViz ( )
static

Definition at line 59 of file SensorBase.cpp.

◆ loadConfigFrom()

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

Loads the parameters common to all sensors. Should be overriden, and they call to this base method.

Reimplemented in mvsim::DepthCameraSensor, mvsim::LaserScanner, mvsim::Lidar3D, mvsim::IMU, and mvsim::CameraSensor.

Definition at line 249 of file SensorBase.cpp.

◆ make_sure_we_have_a_name()

void SensorBase::make_sure_we_have_a_name ( const std::string &  prefix)
protected

Assign a sensible default name/sensor label if none is provided:

Definition at line 271 of file SensorBase.cpp.

◆ parseSensorPublish()

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

Definition at line 129 of file SensorBase.cpp.

◆ registerOnServer()

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

Reimplemented from mvsim::Simulable.

Definition at line 237 of file SensorBase.cpp.

◆ RegisterSensorFOVViz()

void SensorBase::RegisterSensorFOVViz ( const std::shared_ptr< mrpt::opengl::CSetOfObjects > &  o)
static

Definition at line 71 of file SensorBase.cpp.

◆ RegisterSensorOriginViz()

void SensorBase::RegisterSensorOriginViz ( const std::shared_ptr< mrpt::opengl::CSetOfObjects > &  o)
static

Definition at line 76 of file SensorBase.cpp.

◆ reportNewObservation()

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

Definition at line 160 of file SensorBase.cpp.

◆ reportNewObservation_lidar_2d()

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

Definition at line 201 of file SensorBase.cpp.

◆ sensor_period()

double mvsim::SensorBase::sensor_period ( ) const
inline

Definition at line 61 of file SensorBase.h.

◆ should_simulate_sensor()

bool SensorBase::should_simulate_sensor ( const TSimulContext context)
protected

Should be called within each derived class simul_post_timestep() method to update sensor_last_timestamp_ and check if the sensor should be simulated now, given the current simulation time, and the sensor rate in sensor_period_.

Returns
true if it is now time to simulate a new sensor reading, false otherwise.

Definition at line 283 of file SensorBase.cpp.

◆ simulateOn3DScene()

virtual void mvsim::SensorBase::simulateOn3DScene ( [[maybe_unused] ] mrpt::opengl::COpenGLScene &  gl_scene)
inlinevirtual

Definition at line 46 of file SensorBase.h.

◆ world() [1/2]

World* mvsim::SensorBase::world ( )
inlineprotected

Definition at line 76 of file SensorBase.h.

◆ world() [2/2]

const World* mvsim::SensorBase::world ( ) const
inlineprotected

Definition at line 77 of file SensorBase.h.

Member Data Documentation

◆ publishTopic_

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

Publish to MVSIM ZMQ topic stream, if not empty (default)

Definition at line 89 of file SensorBase.h.

◆ rawlog_io_

std::shared_ptr<mrpt::io::CFileGZOutputStream> mvsim::SensorBase::rawlog_io_
protected

Definition at line 83 of file SensorBase.h.

◆ save_to_rawlog_

std::string mvsim::SensorBase::save_to_rawlog_
protected

Definition at line 82 of file SensorBase.h.

◆ sensor_last_timestamp_

double mvsim::SensorBase::sensor_last_timestamp_ = 0
protected

The last sensor reading timestamp. See sensor_period_

Definition at line 86 of file SensorBase.h.

◆ sensor_period_

double mvsim::SensorBase::sensor_period_ = 0.1
protected

Generate one sensor reading every this period s

Definition at line 80 of file SensorBase.h.

◆ varValues_

std::map<std::string, std::string> mvsim::SensorBase::varValues_
protected

Filled in by SensorBase::loadConfigFrom()

Definition at line 92 of file SensorBase.h.

◆ vehicle_

Simulable& mvsim::SensorBase::vehicle_
protected

The vehicle this sensor is attached to.

Definition at line 74 of file SensorBase.h.


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


mvsim
Author(s):
autogenerated on Tue Jul 4 2023 03:08:23