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

#include <LaserScanner.h>

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

Public Member Functions

 LaserScanner (VehicleBase &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 void simul_post_timestep (const TSimulContext &context) override
 
virtual void simul_pre_timestep (const TSimulContext &context) override
 
virtual ~LaserScanner ()
 
- Public Member Functions inherited from mvsim::SensorBase
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
 
void resetCollisionFlag ()
 
void setName (const std::string &s)
 
void setPose (const mrpt::math::TPose3D &p) const
 
void setTwist (const mrpt::math::TTwist2D &dq) const
 

Protected Member Functions

virtual void internalGuiUpdate (mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override
 
- Protected Member Functions inherited from mvsim::SensorBase
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 ()
 
bool parseVisual (const rapidxml::xml_node< char > *visual_node)
 

Protected Attributes

double m_angleStdNoise
 
mrpt::opengl::CPlanarLaserScan::Ptr m_gl_scan
 
std::mutex m_gui_mtx
 
bool m_gui_uptodate = false
 
mrpt::obs::CObservation2DRangeScan::Ptr m_last_scan
 
mrpt::obs::CObservation2DRangeScan::Ptr m_last_scan2gui
 
std::mutex m_last_scan_cs
 
std::string m_name
 sensor label/name More...
 
double m_rangeStdNoise
 
mrpt::obs::CObservation2DRangeScan m_scan_model
 
bool m_see_fixtures
 
mrpt::poses::CPose2D m_sensor_pose_on_veh
 
float m_viz_pointSize = 3.0f
 
bool m_viz_visiblePlane = false
 
bool m_viz_visiblePoints = false
 
int m_z_order
 to help rendering multiple scans More...
 
- Protected Attributes inherited from mvsim::SensorBase
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
 

Additional Inherited Members

- Public Types inherited from mvsim::SensorBase
using Ptr = std::shared_ptr< SensorBase >
 
- Public Types inherited from mvsim::Simulable
using Ptr = std::shared_ptr< Simulable >
 
- Static Public Member Functions inherited from mvsim::SensorBase
static SensorBase::Ptr factory (VehicleBase &parent, const rapidxml::xml_node< char > *xml_node)
 
- Public Attributes inherited from mvsim::SensorBase
double m_sensor_period
 

Detailed Description

Definition at line 21 of file LaserScanner.h.

Constructor & Destructor Documentation

LaserScanner::LaserScanner ( VehicleBase parent,
const rapidxml::xml_node< char > *  root 
)

Definition at line 25 of file LaserScanner.cpp.

LaserScanner::~LaserScanner ( )
virtual

Definition at line 36 of file LaserScanner.cpp.

Member Function Documentation

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

Implements mvsim::VisualObject.

Definition at line 89 of file LaserScanner.cpp.

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

Implements mvsim::SensorBase.

Definition at line 37 of file LaserScanner.cpp.

void mvsim::LaserScanner::poses_mutex_lock ( )
inlineoverridevirtual

Implements mvsim::Simulable.

Definition at line 34 of file LaserScanner.h.

void mvsim::LaserScanner::poses_mutex_unlock ( )
inlineoverridevirtual

Implements mvsim::Simulable.

Definition at line 35 of file LaserScanner.h.

void LaserScanner::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 m_q, m_dq)

Reimplemented from mvsim::Simulable.

Definition at line 133 of file LaserScanner.cpp.

void LaserScanner::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 127 of file LaserScanner.cpp.

Member Data Documentation

double mvsim::LaserScanner::m_angleStdNoise
protected

Definition at line 45 of file LaserScanner.h.

mrpt::opengl::CPlanarLaserScan::Ptr mvsim::LaserScanner::m_gl_scan
protected

Definition at line 67 of file LaserScanner.h.

std::mutex mvsim::LaserScanner::m_gui_mtx
protected

Definition at line 66 of file LaserScanner.h.

bool mvsim::LaserScanner::m_gui_uptodate = false
protected

Whether m_gl_scan has to be updated upon next call of internalGuiUpdate() from m_last_scan2gui

Definition at line 65 of file LaserScanner.h.

mrpt::obs::CObservation2DRangeScan::Ptr mvsim::LaserScanner::m_last_scan
protected

Last simulated scan

Definition at line 60 of file LaserScanner.h.

mrpt::obs::CObservation2DRangeScan::Ptr mvsim::LaserScanner::m_last_scan2gui
protected

Definition at line 61 of file LaserScanner.h.

std::mutex mvsim::LaserScanner::m_last_scan_cs
protected

Definition at line 58 of file LaserScanner.h.

std::string mvsim::LaserScanner::m_name
protected

sensor label/name

Definition at line 43 of file LaserScanner.h.

double mvsim::LaserScanner::m_rangeStdNoise
protected

Definition at line 44 of file LaserScanner.h.

mrpt::obs::CObservation2DRangeScan mvsim::LaserScanner::m_scan_model
protected

Definition at line 56 of file LaserScanner.h.

bool mvsim::LaserScanner::m_see_fixtures
protected

Whether all box2d "fixtures" are visible (solid) or not (Default=true)

Definition at line 48 of file LaserScanner.h.

mrpt::poses::CPose2D mvsim::LaserScanner::m_sensor_pose_on_veh
protected

Definition at line 42 of file LaserScanner.h.

float mvsim::LaserScanner::m_viz_pointSize = 3.0f
protected

Definition at line 52 of file LaserScanner.h.

bool mvsim::LaserScanner::m_viz_visiblePlane = false
protected

Definition at line 50 of file LaserScanner.h.

bool mvsim::LaserScanner::m_viz_visiblePoints = false
protected

Definition at line 51 of file LaserScanner.h.

int mvsim::LaserScanner::m_z_order
protected

to help rendering multiple scans

Definition at line 41 of file LaserScanner.h.


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


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