DepthCameraSensor.h
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2023 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 {
34 {
36 
37  public:
39  virtual ~DepthCameraSensor();
40 
41  // See docs in base class
42  virtual void loadConfigFrom(const rapidxml::xml_node<char>* root) override;
43 
44  virtual void simul_pre_timestep(const TSimulContext& context) override;
45  virtual void simul_post_timestep(const TSimulContext& context) override;
46 
47  void simulateOn3DScene(mrpt::opengl::COpenGLScene& gl_scene) override;
48 
49  void freeOpenGLResources() override;
50 
51  protected:
52  virtual void internalGuiUpdate(
53  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
54  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& physical,
55  bool childrenOnly) override;
56 
57  // Store here all sensor intrinsic parameters. This obj will be copied as a
58  // "pattern" to fill it with actual scan data.
59  mrpt::obs::CObservation3DRangeScan sensor_params_;
60 
61  std::mutex last_obs_cs_;
63  mrpt::obs::CObservation3DRangeScan::Ptr last_obs_;
64  mrpt::obs::CObservation3DRangeScan::Ptr last_obs2gui_;
65 
66  // Note: we need 2 to support different resolutions for RGB vs Depth.
67  std::shared_ptr<mrpt::opengl::CFBORender> fbo_renderer_rgb_,
69 
72  bool gui_uptodate_ = false;
73  mrpt::opengl::CPointCloudColoured::Ptr gl_obs_;
74 
75  std::optional<TSimulContext> has_to_render_;
76  std::mutex has_to_render_mtx_;
77 
78  float rgbClipMin_ = 1e-2, rgbClipMax_ = 1e+4;
79  float depth_clip_min_ = 0.1, depth_clip_max_ = 15.0;
80  float depth_resolution_ = 1e-3;
81 
82  bool sense_depth_ = true;
83  bool sense_rgb_ = true;
84 
85  float depth_noise_sigma_ = 1e-3;
86  bool show_3d_pointcloud_ = false;
87 
88  mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_,
90  mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_, gl_sensor_frustum_;
91 
92  mrpt::math::CMatrixFloat depthImage_; // to avoid memory allocs
93 };
94 } // namespace mvsim
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_rgb_
mrpt::opengl::CPointCloudColoured::Ptr gl_obs_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
bool sense_depth_
Simulate the DEPTH sensor part.
mrpt::math::CMatrixFloat depthImage_
DepthCameraSensor(Simulable &parent, const rapidxml::xml_node< char > *root)
virtual void simul_pre_timestep(const TSimulContext &context) override
void freeOpenGLResources() override
mrpt::obs::CObservation3DRangeScan sensor_params_
std::optional< TSimulContext > has_to_render_
bool sense_rgb_
Simulate the RGB sensor part.
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
#define DECLARES_REGISTER_SENSOR(CLASS_NAME)
Definition: SensorBase.h:118
void simulateOn3DScene(mrpt::opengl::COpenGLScene &gl_scene) override
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_
mrpt::obs::CObservation3DRangeScan::Ptr last_obs2gui_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_frustum_
mrpt::obs::CObservation3DRangeScan::Ptr last_obs_
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_depth_
virtual void internalGuiUpdate(const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
virtual void simul_post_timestep(const TSimulContext &context) override


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