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

A 2D lidar scanner, with FOV up to 360 degrees. More...

#include <LaserScanner.h>

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

Public Member Functions

void freeOpenGLResources () override
 
 LaserScanner (Simulable &parent, const rapidxml::xml_node< char > *root)
 
virtual void loadConfigFrom (const rapidxml::xml_node< char > *root) override
 
void registerOnServer (mvsim::Client &c) override
 
virtual void simul_post_timestep (const TSimulContext &context) override
 
virtual void simul_pre_timestep (const TSimulContext &context) override
 
void simulateOn3DScene (mrpt::opengl::COpenGLScene &gl_scene) override
 
virtual ~LaserScanner ()
 
- Public Member Functions inherited from mvsim::SensorBase
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 ()
 
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
 
 Simulable (World *parent)
 

Protected Member Functions

void internal_simulate_lidar_2d_mode (const TSimulContext &context)
 
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::SensorBase
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)
 
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::vector< size_t > angleIdx2pixelIdx_
 
std::vector< float > angleIdx2secant_
 
double angleStdNoise_ = mrpt::DEG2RAD(0.01)
 
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_depth_
 
mrpt::opengl::CPlanarLaserScan::Ptr gl_scan_
 
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_
 
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_
 
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
 
bool gui_uptodate_ = false
 
std::optional< TSimulContexthas_to_render_
 
std::mutex has_to_render_mtx_
 
bool ignore_parent_body_ = false
 
mrpt::obs::CObservation2DRangeScan::Ptr last_scan2gui_
 
mrpt::obs::CObservation2DRangeScan::Ptr last_scan_
 
std::mutex last_scan_cs_
 
double rangeStdNoise_ = 0.01
 
bool raytrace_3d_ = false
 
mrpt::obs::CObservation2DRangeScan scan_model_
 
bool see_fixtures_ = true
 
mrpt::poses::CPose2D sensor_pose_on_veh_
 
mrpt::img::TColor viz_planeColor_ = {0x00, 0x00, 0xff, 0x10}
 
mrpt::img::TColor viz_pointsColor_ = {0xff, 0x00, 0x00, 0x80}
 
float viz_pointSize_ = 3.0f
 
bool viz_visibleLines_ = true
 
bool viz_visiblePlane_ = false
 
bool viz_visiblePoints_ = false
 
int z_order_
 to help rendering multiple scans More...
 
- Protected Attributes inherited from mvsim::SensorBase
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

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

Detailed Description

A 2D lidar scanner, with FOV up to 360 degrees.

There are two working modes:

Definition at line 31 of file LaserScanner.h.

Constructor & Destructor Documentation

◆ LaserScanner()

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

Definition at line 31 of file LaserScanner.cpp.

◆ ~LaserScanner()

LaserScanner::~LaserScanner ( )
virtual

Definition at line 38 of file LaserScanner.cpp.

Member Function Documentation

◆ freeOpenGLResources()

void LaserScanner::freeOpenGLResources ( )
overridevirtual

Reimplemented from mvsim::Simulable.

Definition at line 433 of file LaserScanner.cpp.

◆ internal_simulate_lidar_2d_mode()

void LaserScanner::internal_simulate_lidar_2d_mode ( const TSimulContext context)
protected

Definition at line 234 of file LaserScanner.cpp.

◆ internalGuiUpdate()

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

◆ loadConfigFrom()

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

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

Reimplemented from mvsim::SensorBase.

Definition at line 40 of file LaserScanner.cpp.

◆ registerOnServer()

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

Reimplemented from mvsim::Simulable.

Definition at line 688 of file LaserScanner.cpp.

◆ simul_post_timestep()

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 q_, dq_)

Reimplemented from mvsim::Simulable.

Definition at line 203 of file LaserScanner.cpp.

◆ simul_pre_timestep()

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 197 of file LaserScanner.cpp.

◆ simulateOn3DScene()

void LaserScanner::simulateOn3DScene ( mrpt::opengl::COpenGLScene &  gl_scene)
override

Definition at line 439 of file LaserScanner.cpp.

Member Data Documentation

◆ angleIdx2pixelIdx_

std::vector<size_t> mvsim::LaserScanner::angleIdx2pixelIdx_
protected

Definition at line 102 of file LaserScanner.h.

◆ angleIdx2secant_

std::vector<float> mvsim::LaserScanner::angleIdx2secant_
protected

Definition at line 103 of file LaserScanner.h.

◆ angleStdNoise_

double mvsim::LaserScanner::angleStdNoise_ = mrpt::DEG2RAD(0.01)
protected

Definition at line 61 of file LaserScanner.h.

◆ fbo_renderer_depth_

std::shared_ptr<mrpt::opengl::CFBORender> mvsim::LaserScanner::fbo_renderer_depth_
protected

Definition at line 100 of file LaserScanner.h.

◆ gl_scan_

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

Definition at line 92 of file LaserScanner.h.

◆ gl_sensor_fov_

mrpt::opengl::CSetOfObjects::Ptr mvsim::LaserScanner::gl_sensor_fov_
protected

Definition at line 95 of file LaserScanner.h.

◆ gl_sensor_origin_

mrpt::opengl::CSetOfObjects::Ptr mvsim::LaserScanner::gl_sensor_origin_
protected

Definition at line 93 of file LaserScanner.h.

◆ gl_sensor_origin_corner_

mrpt::opengl::CSetOfObjects::Ptr mvsim::LaserScanner::gl_sensor_origin_corner_
protected

Definition at line 93 of file LaserScanner.h.

◆ gui_uptodate_

bool mvsim::LaserScanner::gui_uptodate_ = false
protected

Whether gl_scan_ has to be updated upon next call of internalGuiUpdate() from last_scan2gui_

Definition at line 90 of file LaserScanner.h.

◆ has_to_render_

std::optional<TSimulContext> mvsim::LaserScanner::has_to_render_
protected

Definition at line 97 of file LaserScanner.h.

◆ has_to_render_mtx_

std::mutex mvsim::LaserScanner::has_to_render_mtx_
protected

Definition at line 98 of file LaserScanner.h.

◆ ignore_parent_body_

bool mvsim::LaserScanner::ignore_parent_body_ = false
protected

Definition at line 70 of file LaserScanner.h.

◆ last_scan2gui_

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

Definition at line 86 of file LaserScanner.h.

◆ last_scan_

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

Last simulated scan

Definition at line 85 of file LaserScanner.h.

◆ last_scan_cs_

std::mutex mvsim::LaserScanner::last_scan_cs_
protected

Definition at line 83 of file LaserScanner.h.

◆ rangeStdNoise_

double mvsim::LaserScanner::rangeStdNoise_ = 0.01
protected

Definition at line 60 of file LaserScanner.h.

◆ raytrace_3d_

bool mvsim::LaserScanner::raytrace_3d_ = false
protected

If enabled, use realistic 3D depth measurement using the scene 3D model, instead of 2D "fixtures" used for collisions.

Definition at line 68 of file LaserScanner.h.

◆ scan_model_

mrpt::obs::CObservation2DRangeScan mvsim::LaserScanner::scan_model_
protected

Definition at line 81 of file LaserScanner.h.

◆ see_fixtures_

bool mvsim::LaserScanner::see_fixtures_ = true
protected

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

Definition at line 64 of file LaserScanner.h.

◆ sensor_pose_on_veh_

mrpt::poses::CPose2D mvsim::LaserScanner::sensor_pose_on_veh_
protected

Definition at line 59 of file LaserScanner.h.

◆ viz_planeColor_

mrpt::img::TColor mvsim::LaserScanner::viz_planeColor_ = {0x00, 0x00, 0xff, 0x10}
protected

Definition at line 77 of file LaserScanner.h.

◆ viz_pointsColor_

mrpt::img::TColor mvsim::LaserScanner::viz_pointsColor_ = {0xff, 0x00, 0x00, 0x80}
protected

Definition at line 76 of file LaserScanner.h.

◆ viz_pointSize_

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

Definition at line 75 of file LaserScanner.h.

◆ viz_visibleLines_

bool mvsim::LaserScanner::viz_visibleLines_ = true
protected

Definition at line 73 of file LaserScanner.h.

◆ viz_visiblePlane_

bool mvsim::LaserScanner::viz_visiblePlane_ = false
protected

Definition at line 72 of file LaserScanner.h.

◆ viz_visiblePoints_

bool mvsim::LaserScanner::viz_visiblePoints_ = false
protected

Definition at line 74 of file LaserScanner.h.

◆ z_order_

int mvsim::LaserScanner::z_order_
protected

to help rendering multiple scans

Definition at line 58 of file LaserScanner.h.


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


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