DepthCameraSensor.h
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2024 Jose Luis Blanco Claraco |
5  | Copyright (C) 2017 Borys Tymchenko (Odessa Polytechnic University) |
6  | Distributed under 3-clause BSD License |
7  | See COPYING |
8  +-------------------------------------------------------------------------+ */
9 
10 #pragma once
11 
12 #include <mrpt/obs/CObservation3DRangeScan.h>
13 #include <mrpt/opengl/CFBORender.h>
14 #include <mrpt/opengl/CPointCloudColoured.h>
16 
17 #include <mutex>
18 
19 namespace mvsim
20 {
35 {
37 
38  public:
40  virtual ~DepthCameraSensor();
41 
42  // See docs in base class
43  virtual void loadConfigFrom(const rapidxml::xml_node<char>* root) override;
44 
45  virtual void simul_pre_timestep(const TSimulContext& context) override;
46  virtual void simul_post_timestep(const TSimulContext& context) override;
47 
48  void simulateOn3DScene(mrpt::opengl::COpenGLScene& gl_scene) override;
49 
50  void freeOpenGLResources() override;
51 
52  protected:
53  virtual void internalGuiUpdate(
54  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
55  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& physical, bool childrenOnly) override;
56 
57  void notifySimulableSetPose(const mrpt::math::TPose3D& newPose) override;
58 
59  mrpt::math::TPose3D getRelativePose() const override
60  {
61  return sensor_params_.sensorPose.asTPose();
62  }
63  void setRelativePose(const mrpt::math::TPose3D& p) override
64  {
65  sensor_params_.setSensorPose(mrpt::poses::CPose3D(p));
66  }
67 
68  // Store here all sensor intrinsic parameters. This obj will be copied as a
69  // "pattern" to fill it with actual scan data.
70  mrpt::obs::CObservation3DRangeScan sensor_params_;
71 
72  std::mutex last_obs_cs_;
74  mrpt::obs::CObservation3DRangeScan::Ptr last_obs_;
75  mrpt::obs::CObservation3DRangeScan::Ptr last_obs2gui_;
76 
77  // Note: we need 2 to support different resolutions for RGB vs Depth.
78  std::shared_ptr<mrpt::opengl::CFBORender> fbo_renderer_rgb_, fbo_renderer_depth_;
79 
82  bool gui_uptodate_ = false;
83  mrpt::opengl::CPointCloudColoured::Ptr gl_obs_;
84 
85  std::optional<TSimulContext> has_to_render_;
86  std::mutex has_to_render_mtx_;
87 
88  float rgbClipMin_ = 1e-2, rgbClipMax_ = 1e+4;
89  float depth_clip_min_ = 0.1, depth_clip_max_ = 15.0;
90  float depth_resolution_ = 1e-3;
91 
92  bool sense_depth_ = true;
93  bool sense_rgb_ = true;
94 
95  float depth_noise_sigma_ = 1e-3;
96  bool show_3d_pointcloud_ = false;
97 
98  mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_, gl_sensor_origin_corner_;
99  mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_, gl_sensor_frustum_;
100 
101  mrpt::math::CMatrixFloat depthImage_; // to avoid memory allocs
102 };
103 } // namespace mvsim
mvsim::VisualObject::parent
World * parent()
Definition: VisualObject.h:51
mvsim
Definition: Client.h:21
mvsim::DepthCameraSensor::fbo_renderer_rgb_
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_rgb_
Definition: DepthCameraSensor.h:78
mvsim::DepthCameraSensor::setRelativePose
void setRelativePose(const mrpt::math::TPose3D &p) override
Definition: DepthCameraSensor.h:63
mvsim::DepthCameraSensor::depthImage_
mrpt::math::CMatrixFloat depthImage_
Definition: DepthCameraSensor.h:101
mvsim::DepthCameraSensor::depth_clip_max_
float depth_clip_max_
Definition: DepthCameraSensor.h:89
mvsim::DepthCameraSensor::gui_uptodate_
bool gui_uptodate_
Definition: DepthCameraSensor.h:82
mvsim::SensorBase
Virtual base class for all sensors.
Definition: SensorBase.h:34
mvsim::DepthCameraSensor::show_3d_pointcloud_
bool show_3d_pointcloud_
Definition: DepthCameraSensor.h:96
mvsim::DepthCameraSensor::gl_sensor_fov_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_
Definition: DepthCameraSensor.h:99
mvsim::DepthCameraSensor::internalGuiUpdate
virtual void internalGuiUpdate(const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
Definition: DepthCameraSensor.cpp:112
mvsim::DepthCameraSensor::fbo_renderer_depth_
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_depth_
Definition: DepthCameraSensor.h:78
mvsim::DepthCameraSensor::DepthCameraSensor
DepthCameraSensor(Simulable &parent, const rapidxml::xml_node< char > *root)
Definition: DepthCameraSensor.cpp:25
mvsim::TSimulContext
Definition: basic_types.h:58
mvsim::DepthCameraSensor::gl_sensor_origin_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_
Definition: DepthCameraSensor.h:98
mvsim::DepthCameraSensor::last_obs_
mrpt::obs::CObservation3DRangeScan::Ptr last_obs_
Definition: DepthCameraSensor.h:74
mvsim::DepthCameraSensor::getRelativePose
mrpt::math::TPose3D getRelativePose() const override
Definition: DepthCameraSensor.h:59
mvsim::DepthCameraSensor::simulateOn3DScene
void simulateOn3DScene(mrpt::opengl::COpenGLScene &gl_scene) override
Definition: DepthCameraSensor.cpp:206
mvsim::DepthCameraSensor::simul_post_timestep
virtual void simul_post_timestep(const TSimulContext &context) override
Definition: DepthCameraSensor.cpp:414
mvsim::DepthCameraSensor::gl_obs_
mrpt::opengl::CPointCloudColoured::Ptr gl_obs_
Definition: DepthCameraSensor.h:83
mvsim::DepthCameraSensor::has_to_render_mtx_
std::mutex has_to_render_mtx_
Definition: DepthCameraSensor.h:86
mvsim::DepthCameraSensor::sense_depth_
bool sense_depth_
Simulate the DEPTH sensor part.
Definition: DepthCameraSensor.h:92
mvsim::DepthCameraSensor::sense_rgb_
bool sense_rgb_
Simulate the RGB sensor part.
Definition: DepthCameraSensor.h:93
mvsim::DepthCameraSensor::gl_sensor_frustum_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_frustum_
Definition: DepthCameraSensor.h:99
mvsim::DepthCameraSensor::simul_pre_timestep
virtual void simul_pre_timestep(const TSimulContext &context) override
Definition: DepthCameraSensor.cpp:204
rapidxml::xml_node< char >
mvsim::DepthCameraSensor::depth_noise_sigma_
float depth_noise_sigma_
Definition: DepthCameraSensor.h:95
mvsim::Simulable
Definition: Simulable.h:39
mvsim::DepthCameraSensor::rgbClipMin_
float rgbClipMin_
Definition: DepthCameraSensor.h:88
mvsim::DepthCameraSensor::rgbClipMax_
float rgbClipMax_
Definition: DepthCameraSensor.h:88
mvsim::DepthCameraSensor::~DepthCameraSensor
virtual ~DepthCameraSensor()
Definition: DepthCameraSensor.cpp:31
root
root
mvsim::DepthCameraSensor::gl_sensor_origin_corner_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
Definition: DepthCameraSensor.h:98
mvsim::DepthCameraSensor
Definition: DepthCameraSensor.h:34
mvsim::DepthCameraSensor::notifySimulableSetPose
void notifySimulableSetPose(const mrpt::math::TPose3D &newPose) override
Definition: DepthCameraSensor.cpp:429
mvsim::DepthCameraSensor::has_to_render_
std::optional< TSimulContext > has_to_render_
Definition: DepthCameraSensor.h:85
mvsim::DepthCameraSensor::last_obs_cs_
std::mutex last_obs_cs_
Definition: DepthCameraSensor.h:72
SensorBase.h
mvsim::DepthCameraSensor::loadConfigFrom
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
Definition: DepthCameraSensor.cpp:33
DECLARES_REGISTER_SENSOR
#define DECLARES_REGISTER_SENSOR(CLASS_NAME)
Definition: SensorBase.h:120
mvsim::DepthCameraSensor::freeOpenGLResources
void freeOpenGLResources() override
Definition: DepthCameraSensor.cpp:437
mvsim::DepthCameraSensor::sensor_params_
mrpt::obs::CObservation3DRangeScan sensor_params_
Definition: DepthCameraSensor.h:70
mvsim::DepthCameraSensor::last_obs2gui_
mrpt::obs::CObservation3DRangeScan::Ptr last_obs2gui_
Definition: DepthCameraSensor.h:75
mvsim::DepthCameraSensor::depth_clip_min_
float depth_clip_min_
Definition: DepthCameraSensor.h:89
mvsim::DepthCameraSensor::depth_resolution_
float depth_resolution_
Definition: DepthCameraSensor.h:90


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