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

#include <Lidar3D.h>

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

Classes

struct  PerHorzAngleLUT
 
struct  PerRayLUT
 

Public Member Functions

void freeOpenGLResources () override
 
 Lidar3D (Simulable &parent, const rapidxml::xml_node< char > *root)
 
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
 
void simulateOn3DScene (mrpt::opengl::COpenGLScene &gl_scene) override
 
virtual ~Lidar3D ()
 
- 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)
 
Simulablevehicle ()
 
const Simulablevehicle () const
 
virtual ~SensorBase ()
 
- 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
 
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...
 
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, bool notifyChange=true) const
 
void setTwist (const mrpt::math::TTwist2D &dq) const
 
 Simulable (World *parent)
 

Protected Member Functions

mrpt::math::TPose3D getRelativePose () const override
 
virtual void internalGuiUpdate (const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
 
void notifySimulableSetPose (const mrpt::math::TPose3D &newPose) override
 
void setRelativePose (const mrpt::math::TPose3D &p) 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 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

std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_depth_
 
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_
 
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_
 
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
 
mrpt::opengl::CPointCloudColoured::Ptr glPoints_
 
bool gui_uptodate_ = false
 
std::optional< TSimulContexthas_to_render_
 
std::mutex has_to_render_mtx_
 
int horzNumRays_ = 180
 
double horzResolutionFactor_ = 1.0
 
bool ignore_parent_body_ = false
 
mrpt::obs::CObservationPointCloud::Ptr last_scan2gui_
 
mrpt::obs::CObservationPointCloud::Ptr last_scan_
 
std::mutex last_scan_cs_
 
std::vector< PerHorzAngleLUTlut_
 
float maxDepthInterpolationStepHorz_ = 0.10f
 
float maxDepthInterpolationStepVert_ = 0.30f
 
float maxRange_ = 80.0f
 
float minRange_ = 0.01f
 
double rangeStdNoise_ = 0.01
 
mrpt::poses::CPose3D sensorPoseOnVeh_
 
double vertical_fov_ = 30.0
 In degrees !! More...
 
std::vector< double > vertical_ray_angles_
 
std::string vertical_ray_angles_str_
 
int vertNumRays_ = 16
 
double vertResolutionFactor_ = 1.0
 
float viz_pointSize_ = 3.0f
 
- Protected Attributes inherited from mvsim::SensorBase
std::string publishTopic_
 
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 3D LiDAR sensor, with 360 degrees horizontal fielf-of-view, and a configurable vertical FOV. The number of rays in the vertical FOV and the number of samples in each horizontal row are configurable.

Definition at line 30 of file Lidar3D.h.

Constructor & Destructor Documentation

◆ Lidar3D()

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

Definition at line 42 of file Lidar3D.cpp.

◆ ~Lidar3D()

Lidar3D::~Lidar3D ( )
virtual

Definition at line 47 of file Lidar3D.cpp.

Member Function Documentation

◆ freeOpenGLResources()

void Lidar3D::freeOpenGLResources ( )
overridevirtual

Reimplemented from mvsim::Simulable.

Definition at line 194 of file Lidar3D.cpp.

◆ getRelativePose()

mrpt::math::TPose3D mvsim::Lidar3D::getRelativePose ( ) const
inlineoverrideprotectedvirtual

Like getPose(), but gets the relative pose with respect to the parent object, or just exactly like getPose() (global pose) if this is a top-level entity.

Reimplemented from mvsim::Simulable.

Definition at line 53 of file Lidar3D.h.

◆ internalGuiUpdate()

void Lidar3D::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 83 of file Lidar3D.cpp.

◆ loadConfigFrom()

void Lidar3D::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 49 of file Lidar3D.cpp.

◆ notifySimulableSetPose()

void Lidar3D::notifySimulableSetPose ( const mrpt::math::TPose3D &  newPose)
overrideprotected

Definition at line 186 of file Lidar3D.cpp.

◆ setRelativePose()

void mvsim::Lidar3D::setRelativePose ( const mrpt::math::TPose3D &  p)
inlineoverrideprotectedvirtual

Changes the relative pose of this object with respect to its parent, or the global frame if its a top-level entity.

Reimplemented from mvsim::Simulable.

Definition at line 54 of file Lidar3D.h.

◆ simul_post_timestep()

void Lidar3D::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 158 of file Lidar3D.cpp.

◆ simul_pre_timestep()

void Lidar3D::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 155 of file Lidar3D.cpp.

◆ simulateOn3DScene()

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

Definition at line 289 of file Lidar3D.cpp.

Member Data Documentation

◆ fbo_renderer_depth_

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

Definition at line 99 of file Lidar3D.h.

◆ gl_sensor_fov_

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

Definition at line 94 of file Lidar3D.h.

◆ gl_sensor_origin_

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

Definition at line 93 of file Lidar3D.h.

◆ gl_sensor_origin_corner_

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

Definition at line 93 of file Lidar3D.h.

◆ glPoints_

mrpt::opengl::CPointCloudColoured::Ptr mvsim::Lidar3D::glPoints_
protected

Definition at line 92 of file Lidar3D.h.

◆ gui_uptodate_

bool mvsim::Lidar3D::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 Lidar3D.h.

◆ has_to_render_

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

Definition at line 96 of file Lidar3D.h.

◆ has_to_render_mtx_

std::mutex mvsim::Lidar3D::has_to_render_mtx_
protected

Definition at line 97 of file Lidar3D.h.

◆ horzNumRays_

int mvsim::Lidar3D::horzNumRays_ = 180
protected

Definition at line 78 of file Lidar3D.h.

◆ horzResolutionFactor_

double mvsim::Lidar3D::horzResolutionFactor_ = 1.0
protected

Definition at line 79 of file Lidar3D.h.

◆ ignore_parent_body_

bool mvsim::Lidar3D::ignore_parent_body_ = false
protected

Definition at line 62 of file Lidar3D.h.

◆ last_scan2gui_

mrpt::obs::CObservationPointCloud::Ptr mvsim::Lidar3D::last_scan2gui_
protected

Last simulated scan

Definition at line 85 of file Lidar3D.h.

◆ last_scan_

mrpt::obs::CObservationPointCloud::Ptr mvsim::Lidar3D::last_scan_
protected

Definition at line 85 of file Lidar3D.h.

◆ last_scan_cs_

std::mutex mvsim::Lidar3D::last_scan_cs_
protected

Definition at line 86 of file Lidar3D.h.

◆ lut_

std::vector<PerHorzAngleLUT> mvsim::Lidar3D::lut_
protected

Definition at line 111 of file Lidar3D.h.

◆ maxDepthInterpolationStepHorz_

float mvsim::Lidar3D::maxDepthInterpolationStepHorz_ = 0.10f
protected

Definition at line 82 of file Lidar3D.h.

◆ maxDepthInterpolationStepVert_

float mvsim::Lidar3D::maxDepthInterpolationStepVert_ = 0.30f
protected

Definition at line 81 of file Lidar3D.h.

◆ maxRange_

float mvsim::Lidar3D::maxRange_ = 80.0f
protected

Definition at line 66 of file Lidar3D.h.

◆ minRange_

float mvsim::Lidar3D::minRange_ = 0.01f
protected

Definition at line 65 of file Lidar3D.h.

◆ rangeStdNoise_

double mvsim::Lidar3D::rangeStdNoise_ = 0.01
protected

Definition at line 61 of file Lidar3D.h.

◆ sensorPoseOnVeh_

mrpt::poses::CPose3D mvsim::Lidar3D::sensorPoseOnVeh_
protected

Definition at line 59 of file Lidar3D.h.

◆ vertical_fov_

double mvsim::Lidar3D::vertical_fov_ = 30.0
protected

In degrees !!

vertical FOV will be symmetric above and below the horizontal line, unless vertical_ray_angles_str_ is set

Definition at line 70 of file Lidar3D.h.

◆ vertical_ray_angles_

std::vector<double> mvsim::Lidar3D::vertical_ray_angles_
protected

Upon initialization, vertical_rays_str_ is parsed in this vector of angles in radians.

Definition at line 115 of file Lidar3D.h.

◆ vertical_ray_angles_str_

std::string mvsim::Lidar3D::vertical_ray_angles_str_
protected

If not empty, will define the list of ray vertical angles, in degrees, separated by whitespaces. Positive angles are above, negative below the horizontal plane.

Definition at line 76 of file Lidar3D.h.

◆ vertNumRays_

int mvsim::Lidar3D::vertNumRays_ = 16
protected

Definition at line 78 of file Lidar3D.h.

◆ vertResolutionFactor_

double mvsim::Lidar3D::vertResolutionFactor_ = 1.0
protected

Definition at line 80 of file Lidar3D.h.

◆ viz_pointSize_

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

Definition at line 64 of file Lidar3D.h.


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


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