#include <DepthCameraSensor.h>

Public Member Functions | |
| DepthCameraSensor (Simulable &parent, const rapidxml::xml_node< char > *root) | |
| void | freeOpenGLResources () override |
| 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 | ~DepthCameraSensor () |
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) |
| Simulable & | vehicle () |
| const Simulable & | vehicle () 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) |
| World * | parent () |
| const World * | parent () 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)) |
| b2Body * | b2d_body () |
| const b2Body * | b2d_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... | |
| 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, 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) |
| World * | world () |
| const World * | world () 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 | |
| float | depth_clip_max_ = 15.0 |
| float | depth_clip_min_ = 0.1 |
| float | depth_noise_sigma_ = 1e-3 |
| float | depth_resolution_ = 1e-3 |
| mrpt::math::CMatrixFloat | depthImage_ |
| std::shared_ptr< mrpt::opengl::CFBORender > | fbo_renderer_depth_ |
| std::shared_ptr< mrpt::opengl::CFBORender > | fbo_renderer_rgb_ |
| mrpt::opengl::CPointCloudColoured::Ptr | gl_obs_ |
| mrpt::opengl::CSetOfObjects::Ptr | gl_sensor_fov_ |
| mrpt::opengl::CSetOfObjects::Ptr | gl_sensor_frustum_ |
| 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_ |
| mrpt::obs::CObservation3DRangeScan::Ptr | last_obs2gui_ |
| mrpt::obs::CObservation3DRangeScan::Ptr | last_obs_ |
| std::mutex | last_obs_cs_ |
| float | rgbClipMax_ = 1e+4 |
| float | rgbClipMin_ = 1e-2 |
| bool | sense_depth_ = true |
| Simulate the DEPTH sensor part. More... | |
| bool | sense_rgb_ = true |
| Simulate the RGB sensor part. More... | |
| mrpt::obs::CObservation3DRangeScan | sensor_params_ |
| bool | show_3d_pointcloud_ = false |
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... | |
| Simulable & | vehicle_ |
| 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 |
| World * | world_ |
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 |
"RGB+D" or just "D" (depth without RGB) camera sensor on board a vehicle.
Use the XML parameters:
to optionally disable the simulation of either the RGB or Depth part of the outcoming mrpt::obs::CObservation3DRangeScan observations.
Definition at line 34 of file DepthCameraSensor.h.
| DepthCameraSensor::DepthCameraSensor | ( | Simulable & | parent, |
| const rapidxml::xml_node< char > * | root | ||
| ) |
Definition at line 25 of file DepthCameraSensor.cpp.
|
virtual |
Definition at line 31 of file DepthCameraSensor.cpp.
|
overridevirtual |
Reimplemented from mvsim::Simulable.
Definition at line 437 of file DepthCameraSensor.cpp.
|
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 59 of file DepthCameraSensor.h.
|
overrideprotectedvirtual |
Implements mvsim::VisualObject.
Definition at line 112 of file DepthCameraSensor.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 33 of file DepthCameraSensor.cpp.
|
overrideprotected |
Definition at line 429 of file DepthCameraSensor.cpp.
|
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 63 of file DepthCameraSensor.h.
|
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 414 of file DepthCameraSensor.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 204 of file DepthCameraSensor.cpp.
|
override |
Definition at line 206 of file DepthCameraSensor.cpp.
|
protected |
Definition at line 89 of file DepthCameraSensor.h.
|
protected |
Definition at line 89 of file DepthCameraSensor.h.
|
protected |
Definition at line 95 of file DepthCameraSensor.h.
|
protected |
Definition at line 90 of file DepthCameraSensor.h.
|
protected |
Definition at line 101 of file DepthCameraSensor.h.
|
protected |
Definition at line 78 of file DepthCameraSensor.h.
|
protected |
Definition at line 78 of file DepthCameraSensor.h.
|
protected |
Definition at line 83 of file DepthCameraSensor.h.
|
protected |
Definition at line 99 of file DepthCameraSensor.h.
|
protected |
Definition at line 99 of file DepthCameraSensor.h.
|
protected |
Definition at line 98 of file DepthCameraSensor.h.
|
protected |
Definition at line 98 of file DepthCameraSensor.h.
|
protected |
Whether gl_scan_ has to be updated upon next call of internalGuiUpdate() from last_scan2gui_
Definition at line 82 of file DepthCameraSensor.h.
|
protected |
Definition at line 85 of file DepthCameraSensor.h.
|
protected |
Definition at line 86 of file DepthCameraSensor.h.
|
protected |
Definition at line 75 of file DepthCameraSensor.h.
|
protected |
Last simulated scan
Definition at line 74 of file DepthCameraSensor.h.
|
protected |
Definition at line 72 of file DepthCameraSensor.h.
|
protected |
Definition at line 88 of file DepthCameraSensor.h.
|
protected |
Definition at line 88 of file DepthCameraSensor.h.
|
protected |
Simulate the DEPTH sensor part.
Definition at line 92 of file DepthCameraSensor.h.
|
protected |
Simulate the RGB sensor part.
Definition at line 93 of file DepthCameraSensor.h.
|
protected |
Definition at line 70 of file DepthCameraSensor.h.
|
protected |
Definition at line 96 of file DepthCameraSensor.h.