A 2D lidar scanner, with FOV up to 360 degrees. More...
#include <LaserScanner.h>
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 () |
![]() | |
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 () |
![]() | |
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) |
World * | parent () |
const World * | parent () const |
void | showCollisionShape (bool show) |
VisualObject (World *parent, bool insertCustomVizIntoViz=true, bool insertCustomVizIntoPhysical=true) | |
virtual | ~VisualObject () |
![]() | |
virtual void | apply_force (const mrpt::math::TVector2D &force, const mrpt::math::TPoint2D &applyPoint=mrpt::math::TPoint2D(0, 0)) |
const b2Body * | b2d_body () const |
b2Body * | b2d_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... | |
World * | getSimulableWorldObject () |
const World * | getSimulableWorldObject () const |
mrpt::math::TTwist2D | getTwist () const |
mrpt::math::TTwist2D | getVelocityLocal () const |
bool | hadCollision () const |
bool | isInCollision () const |
virtual VisualObject * | meAsVisualObject () |
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 |
![]() | |
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) |
World * | world () |
const World * | world () const |
![]() | |
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< TSimulContext > | has_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... | |
![]() | |
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... | |
Simulable & | vehicle_ |
The vehicle this sensor is attached to. More... | |
![]() | |
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 |
World * | world_ |
![]() | |
std::string | name_ |
Additional Inherited Members | |
![]() | |
using | Ptr = std::shared_ptr< SensorBase > |
![]() | |
using | Ptr = std::shared_ptr< Simulable > |
![]() | |
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 void | FreeOpenGLResources () |
![]() | |
static double | GeometryEpsilon = 1e-3 |
A 2D lidar scanner, with FOV up to 360 degrees.
There are two working modes:
raytrace_3d=false
: Very fast simulation, applicable to 2D worlds.raytrace_3d=true
: Accurate version using detailed 3D meshes for all available objects in the scene. Definition at line 31 of file LaserScanner.h.
LaserScanner::LaserScanner | ( | Simulable & | parent, |
const rapidxml::xml_node< char > * | root | ||
) |
Definition at line 31 of file LaserScanner.cpp.
|
virtual |
Definition at line 38 of file LaserScanner.cpp.
|
overridevirtual |
Reimplemented from mvsim::Simulable.
Definition at line 433 of file LaserScanner.cpp.
|
protected |
Definition at line 234 of file LaserScanner.cpp.
|
overrideprotectedvirtual |
Implements mvsim::VisualObject.
Definition at line 86 of file LaserScanner.cpp.
|
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.
|
overridevirtual |
Reimplemented from mvsim::Simulable.
Definition at line 688 of file LaserScanner.cpp.
|
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.
|
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.
|
override |
Definition at line 439 of file LaserScanner.cpp.
|
protected |
Definition at line 102 of file LaserScanner.h.
|
protected |
Definition at line 103 of file LaserScanner.h.
|
protected |
Definition at line 61 of file LaserScanner.h.
|
protected |
Definition at line 100 of file LaserScanner.h.
|
protected |
Definition at line 92 of file LaserScanner.h.
|
protected |
Definition at line 95 of file LaserScanner.h.
|
protected |
Definition at line 93 of file LaserScanner.h.
|
protected |
Definition at line 93 of file LaserScanner.h.
|
protected |
Whether gl_scan_ has to be updated upon next call of internalGuiUpdate() from last_scan2gui_
Definition at line 90 of file LaserScanner.h.
|
protected |
Definition at line 97 of file LaserScanner.h.
|
protected |
Definition at line 98 of file LaserScanner.h.
|
protected |
Definition at line 70 of file LaserScanner.h.
|
protected |
Definition at line 86 of file LaserScanner.h.
|
protected |
Last simulated scan
Definition at line 85 of file LaserScanner.h.
|
protected |
Definition at line 83 of file LaserScanner.h.
|
protected |
Definition at line 60 of file LaserScanner.h.
|
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.
|
protected |
Definition at line 81 of file LaserScanner.h.
|
protected |
Whether all box2d "fixtures" are visible (solid) or not (Default=true)
Definition at line 64 of file LaserScanner.h.
|
protected |
Definition at line 59 of file LaserScanner.h.
|
protected |
Definition at line 77 of file LaserScanner.h.
|
protected |
Definition at line 76 of file LaserScanner.h.
|
protected |
Definition at line 75 of file LaserScanner.h.
|
protected |
Definition at line 73 of file LaserScanner.h.
|
protected |
Definition at line 72 of file LaserScanner.h.
|
protected |
Definition at line 74 of file LaserScanner.h.
|
protected |
to help rendering multiple scans
Definition at line 58 of file LaserScanner.h.