DepthCameraSensor.cpp
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 #include <mrpt/core/lock_helper.h>
11 #include <mrpt/opengl/CFrustum.h>
12 #include <mrpt/opengl/COpenGLScene.h>
13 #include <mrpt/opengl/stock_objects.h>
14 #include <mrpt/random.h>
15 #include <mrpt/version.h>
17 #include <mvsim/VehicleBase.h>
18 #include <mvsim/World.h>
19 
20 #include "xml_utils.h"
21 
22 using namespace mvsim;
23 using namespace rapidxml;
24 
26  Simulable& parent, const rapidxml::xml_node<char>* root)
27  : SensorBase(parent)
28 {
30 }
31 
33 
35 {
36  gui_uptodate_ = false;
37 
40 
41  fbo_renderer_depth_.reset();
42  fbo_renderer_rgb_.reset();
43 
44  using namespace mrpt; // _deg
45  sensor_params_.sensorPose =
46  mrpt::poses::CPose3D(0, 0, 0.5, 90.0_deg, 0, 90.0_deg);
47 
48  // Default values:
49  {
50  auto& c = sensor_params_.cameraParamsIntensity;
51  c.ncols = 640;
52  c.nrows = 480;
53  c.cx(c.ncols / 2);
54  c.cy(c.nrows / 2);
55  c.fx(500);
56  c.fy(500);
57  }
58  sensor_params_.cameraParams = sensor_params_.cameraParamsIntensity;
59 
60  // Other scalar params:
61  TParameterDefinitions params;
62  params["pose_3d"] = TParamEntry("%pose3d", &sensor_params_.sensorPose);
63  params["relativePoseIntensityWRTDepth"] =
64  TParamEntry("%pose3d", &sensor_params_.relativePoseIntensityWRTDepth);
65 
66  params["sense_depth"] = TParamEntry("%bool", &sense_depth_);
67  params["sense_rgb"] = TParamEntry("%bool", &sense_rgb_);
68 
69  auto& depthCam = sensor_params_.cameraParams;
70  params["depth_cx"] = TParamEntry("%lf", &depthCam.intrinsicParams(0, 2));
71  params["depth_cy"] = TParamEntry("%lf", &depthCam.intrinsicParams(1, 2));
72  params["depth_fx"] = TParamEntry("%lf", &depthCam.intrinsicParams(0, 0));
73  params["depth_fy"] = TParamEntry("%lf", &depthCam.intrinsicParams(1, 1));
74 
75  unsigned int depth_ncols = depthCam.ncols, depth_nrows = depthCam.nrows;
76  params["depth_ncols"] = TParamEntry("%u", &depth_ncols);
77  params["depth_nrows"] = TParamEntry("%u", &depth_nrows);
78 
79  auto& rgbCam = sensor_params_.cameraParamsIntensity;
80  params["rgb_cx"] = TParamEntry("%lf", &rgbCam.intrinsicParams(0, 2));
81  params["rgb_cy"] = TParamEntry("%lf", &rgbCam.intrinsicParams(1, 2));
82  params["rgb_fx"] = TParamEntry("%lf", &rgbCam.intrinsicParams(0, 0));
83  params["rgb_fy"] = TParamEntry("%lf", &rgbCam.intrinsicParams(1, 1));
84 
85  unsigned int rgb_ncols = depthCam.ncols, rgb_nrows = depthCam.nrows;
86  params["rgb_ncols"] = TParamEntry("%u", &rgb_ncols);
87  params["rgb_nrows"] = TParamEntry("%u", &rgb_nrows);
88 
89  params["rgb_clip_min"] = TParamEntry("%f", &rgbClipMin_);
90  params["rgb_clip_max"] = TParamEntry("%f", &rgbClipMax_);
91  params["depth_clip_min"] = TParamEntry("%f", &depth_clip_min_);
92  params["depth_clip_max"] = TParamEntry("%f", &depth_clip_max_);
93  params["depth_resolution"] = TParamEntry("%f", &depth_resolution_);
94 
95  params["depth_noise_sigma"] = TParamEntry("%f", &depth_noise_sigma_);
96  params["show_3d_pointcloud"] = TParamEntry("%bool", &show_3d_pointcloud_);
97 
98  // Parse XML params:
100 
101  depthCam.ncols = depth_ncols;
102  depthCam.nrows = depth_nrows;
103 
104  rgbCam.ncols = rgb_ncols;
105  rgbCam.nrows = rgb_nrows;
106 
107  // save sensor label here too:
108  sensor_params_.sensorLabel = name_;
109 
110  sensor_params_.maxRange = depth_clip_max_;
111  sensor_params_.rangeUnits = depth_resolution_;
112 }
113 
115  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
116  [[maybe_unused]] const mrpt::optional_ref<mrpt::opengl::COpenGLScene>&
117  physical,
118  [[maybe_unused]] bool childrenOnly)
119 {
120  mrpt::opengl::CSetOfObjects::Ptr glVizSensors;
121  if (viz)
122  {
123  glVizSensors = std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
124  viz->get().getByName("group_sensors_viz"));
125  if (!glVizSensors) return; // may happen during shutdown
126  }
127 
128  // 1st time?
129  if (!gl_obs_ && glVizSensors)
130  {
131  gl_obs_ = mrpt::opengl::CPointCloudColoured::Create();
132  gl_obs_->setPointSize(2.0f);
133  gl_obs_->setLocalRepresentativePoint(
134  sensor_params_.sensorPose.translation());
135  glVizSensors->insert(gl_obs_);
136  }
137 
138  if (!gl_sensor_origin_ && viz)
139  {
140  gl_sensor_origin_ = mrpt::opengl::CSetOfObjects::Create();
141 #if MRPT_VERSION >= 0x270
142  gl_sensor_origin_->castShadows(false);
143 #endif
145  mrpt::opengl::stock_objects::CornerXYZSimple(0.15f);
146 
148 
149  gl_sensor_origin_->setVisibility(false);
150  viz->get().insert(gl_sensor_origin_);
152  }
153  if (!gl_sensor_fov_ && viz)
154  {
155  gl_sensor_fov_ = mrpt::opengl::CSetOfObjects::Create();
156  gl_sensor_fov_->setVisibility(false);
157  viz->get().insert(gl_sensor_fov_);
159  }
160 
161  if (!gui_uptodate_)
162  {
163  {
164  std::lock_guard<std::mutex> csl(last_obs_cs_);
165  if (last_obs2gui_ && glVizSensors->isVisible())
166  {
168  {
169  mrpt::obs::T3DPointsProjectionParams pp;
170  pp.takeIntoAccountSensorPoseOnRobot = true;
171  last_obs2gui_->unprojectInto(*gl_obs_, pp);
172  // gl_obs_->recolorizeByCoordinate() ...??
173  }
174 
175  gl_sensor_origin_corner_->setPose(last_obs2gui_->sensorPose);
176 
177  if (!gl_sensor_frustum_)
178  {
179  gl_sensor_frustum_ = mrpt::opengl::CSetOfObjects::Create();
180 
181  const float frustumScale = 0.4e-3;
182  auto frustum = mrpt::opengl::CFrustum::Create(
183  last_obs2gui_->cameraParams, frustumScale);
184 
185  gl_sensor_frustum_->insert(frustum);
187  }
188 
189  gl_sensor_frustum_->setPose(last_obs2gui_->sensorPose);
190 
191  last_obs2gui_.reset();
192  }
193  }
194  gui_uptodate_ = true;
195  }
196 
197  // Move with vehicle:
198  const auto& p = vehicle_.getPose();
199 
200  if (gl_obs_) gl_obs_->setPose(p);
201  if (gl_sensor_fov_) gl_sensor_fov_->setPose(p);
202  if (gl_sensor_origin_) gl_sensor_origin_->setPose(p);
203 
204  if (glCustomVisual_)
205  glCustomVisual_->setPose(p + sensor_params_.sensorPose.asTPose());
206 }
207 
209  [[maybe_unused]] const TSimulContext& context)
210 {
211 }
212 
214  mrpt::opengl::COpenGLScene& world3DScene)
215 {
216  using namespace mrpt; // _deg
217 
218  {
219  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
220  if (!has_to_render_.has_value()) return;
221  }
222 
223  auto tleWhole =
224  mrpt::system::CTimeLoggerEntry(world_->getTimeLogger(), "sensor.RGBD");
225 
226  auto tle1 = mrpt::system::CTimeLoggerEntry(
227  world_->getTimeLogger(), "sensor.RGBD.acqGuiMtx");
228 
229  tle1.stop();
230 
231  if (glCustomVisual_) glCustomVisual_->setVisibility(false);
232 
233  // Start making a copy of the pattern observation:
234  auto curObsPtr = mrpt::obs::CObservation3DRangeScan::Create(sensor_params_);
235  auto& curObs = *curObsPtr;
236 
237  // Set timestamp:
238  curObs.timestamp = world_->get_simul_timestamp();
239 
240  // Create FBO on first use, now that we are here at the GUI / OpenGL thread.
242  {
243  auto tle2 = mrpt::system::CTimeLoggerEntry(
244  world_->getTimeLogger(), "sensor.RGBD.createFBO");
245 
246  mrpt::opengl::CFBORender::Parameters p;
247  p.width = sensor_params_.cameraParamsIntensity.ncols;
248  p.height = sensor_params_.cameraParamsIntensity.nrows;
249  p.create_EGL_context = world()->sensor_has_to_create_egl_context();
250 
251  fbo_renderer_rgb_ = std::make_shared<mrpt::opengl::CFBORender>(p);
252  }
253 
255  {
256  auto tle2 = mrpt::system::CTimeLoggerEntry(
257  world_->getTimeLogger(), "sensor.RGBD.createFBO");
258 
259  mrpt::opengl::CFBORender::Parameters p;
260  p.width = sensor_params_.cameraParams.ncols;
261  p.height = sensor_params_.cameraParams.nrows;
262  p.create_EGL_context = world()->sensor_has_to_create_egl_context();
263 
264  fbo_renderer_depth_ = std::make_shared<mrpt::opengl::CFBORender>(p);
265  }
266 
267  auto viewport = world3DScene.getViewport();
268 
269  auto* camDepth = fbo_renderer_depth_
270  ? &fbo_renderer_depth_->getCamera(world3DScene)
271  : nullptr;
272  auto* camRGB = fbo_renderer_rgb_
273  ? &fbo_renderer_rgb_->getCamera(world3DScene)
274  : nullptr;
275 
276  const auto fixedAxisConventionRot =
277  mrpt::poses::CPose3D(0, 0, 0, -90.0_deg, 0.0_deg, -90.0_deg);
278 
279  // ----------------------------------------------------------
280  // RGB first with its camera intrinsics & clip distances
281  // ----------------------------------------------------------
282 
283  // RGB camera pose:
284  // vehicle (+) relativePoseOnVehicle (+) relativePoseIntensityWRTDepth
285  //
286  // Note: relativePoseOnVehicle should be (y,p,r)=(-90deg,0,-90deg) to make
287  // the camera to look forward:
288 
289  const auto vehiclePose = mrpt::poses::CPose3D(vehicle_.getPose());
290 
291  const auto depthSensorPose =
292  vehiclePose + curObs.sensorPose + fixedAxisConventionRot;
293 
294  const auto rgbSensorPose =
295  vehiclePose + curObs.sensorPose + curObs.relativePoseIntensityWRTDepth;
296 
297  if (fbo_renderer_rgb_)
298  {
299  auto tle2 = mrpt::system::CTimeLoggerEntry(
300  world_->getTimeLogger(), "sensor.RGBD.renderRGB");
301 
302  camRGB->set6DOFMode(true);
303  camRGB->setProjectiveFromPinhole(curObs.cameraParamsIntensity);
304  camRGB->setPose(rgbSensorPose);
305 
306  // viewport->setCustomBackgroundColor({0.3f, 0.3f, 0.3f, 1.0f});
307  viewport->setViewportClipDistances(rgbClipMin_, rgbClipMax_);
308 
309  fbo_renderer_rgb_->render_RGB(world3DScene, curObs.intensityImage);
310 
311  curObs.hasIntensityImage = true;
312  }
313  else
314  {
315  curObs.hasIntensityImage = false;
316  }
317 
318  // ----------------------------------------------------------
319  // DEPTH camera next
320  // ----------------------------------------------------------
322  {
323  auto tle2 = mrpt::system::CTimeLoggerEntry(
324  world_->getTimeLogger(), "sensor.RGBD.renderD");
325 
326  camDepth->setProjectiveFromPinhole(curObs.cameraParams);
327 
328  // Camera pose: vehicle + relativePoseOnVehicle:
329  // Note: relativePoseOnVehicle should be (y,p,r)=(90deg,0,90deg) to make
330  // the camera to look forward:
331  camDepth->set6DOFMode(true);
332  camDepth->setPose(depthSensorPose);
333 
334  // viewport->setCustomBackgroundColor({0.3f, 0.3f, 0.3f, 1.0f});
335  viewport->setViewportClipDistances(depth_clip_min_, depth_clip_max_);
336 
337  auto tle2c = mrpt::system::CTimeLoggerEntry(
338  world_->getTimeLogger(), "sensor.RGBD.renderD_core");
339 
340  fbo_renderer_depth_->render_depth(world3DScene, depthImage_);
341 
342  tle2c.stop();
343 
344  // Convert depth image:
345  curObs.hasRangeImage = true;
346  curObs.range_is_depth = true;
347 
348  auto tle2cnv = mrpt::system::CTimeLoggerEntry(
349  world_->getTimeLogger(), "sensor.RGBD.renderD_cast");
350 
351  // float -> uint16_t with "curObs.rangeUnits" units:
352  curObs.rangeImage_setSize(depthImage_.rows(), depthImage_.cols());
353  curObs.rangeImage = (depthImage_.asEigen().cwiseMin(curObs.maxRange) /
354  curObs.rangeUnits)
355  .cast<uint16_t>();
356 
357  tle2cnv.stop();
358 
359  // Add random noise:
360  if (depth_noise_sigma_ > 0)
361  {
362  // Each thread must create its own rng:
363  thread_local mrpt::random::CRandomGenerator rng;
364  thread_local std::vector<int16_t> noiseSeq;
365  thread_local size_t noiseIdx = 0;
366  constexpr size_t noiseLen = 7823; // prime
367  if (noiseSeq.empty())
368  {
369  noiseSeq.reserve(noiseLen);
370  for (size_t i = 0; i < noiseLen; i++)
371  {
372  noiseSeq.push_back(static_cast<int16_t>(mrpt::round(
373  rng.drawGaussian1D(0.0, depth_noise_sigma_) /
374  curObs.rangeUnits)));
375  }
376  }
377 
378  auto tle2noise = mrpt::system::CTimeLoggerEntry(
379  world_->getTimeLogger(), "sensor.RGBD.renderD_noise");
380 
381  uint16_t* d = curObs.rangeImage.data();
382  const size_t N = curObs.rangeImage.size();
383 
384  const int16_t maxRangeInts =
385  static_cast<int16_t>(curObs.maxRange / curObs.rangeUnits);
386 
387  for (size_t i = 0; i < N; i++)
388  {
389  if (d[i] == 0) continue; // it was an invalid ray return.
390 
391  const int16_t dNoisy =
392  static_cast<int16_t>(d[i]) + noiseSeq[noiseIdx++];
393 
394  if (noiseIdx >= noiseLen) noiseIdx = 0;
395 
396  if (dNoisy > maxRangeInts) continue;
397 
398  d[i] = static_cast<uint16_t>(dNoisy);
399  }
400  }
401  }
402  else
403  {
404  curObs.hasRangeImage = false;
405  }
406 
407  // Store generated obs:
408  {
409  auto tle3 = mrpt::system::CTimeLoggerEntry(
410  world_->getTimeLogger(), "sensor.RGBD.acqObsMtx");
411 
412  std::lock_guard<std::mutex> csl(last_obs_cs_);
413  last_obs_ = std::move(curObsPtr);
415  }
416 
417  {
418  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
419 
420  auto tlePub = mrpt::system::CTimeLoggerEntry(
421  world_->getTimeLogger(), "sensor.RGBD.report");
422 
424 
425  tlePub.stop();
426 
427  if (glCustomVisual_) glCustomVisual_->setVisibility(true);
428 
429  gui_uptodate_ = false;
430  has_to_render_.reset();
431  }
432 }
433 
434 // Simulate sensor AFTER timestep, with the updated vehicle dynamical state:
436 {
439  {
440  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
441  has_to_render_ = context;
443  }
444 }
445 
447 {
448  fbo_renderer_depth_.reset();
449  fbo_renderer_rgb_.reset();
450 }
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_rgb_
d
bool sensor_has_to_create_egl_context()
Definition: World.cpp:397
mrpt::opengl::CPointCloudColoured::Ptr gl_obs_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
World * world()
Definition: SensorBase.h:76
std::map< std::string, TParamEntry > TParameterDefinitions
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const TParameterDefinitions &params, const std::map< std::string, std::string > &variableNamesValues={}, const char *functionNameContext="", mrpt::system::COutputLogger *logger=nullptr)
Definition: xml_utils.cpp:224
f
mrpt::math::TPose3D getPose() const
Definition: Simulable.cpp:438
bool sense_depth_
Simulate the DEPTH sensor part.
mrpt::math::CMatrixFloat depthImage_
static void RegisterSensorFOVViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
Definition: SensorBase.cpp:71
bool should_simulate_sensor(const TSimulContext &context)
Definition: SensorBase.cpp:283
std::map< std::string, std::string > varValues_
Filled in by SensorBase::loadConfigFrom()
Definition: SensorBase.h:92
DepthCameraSensor(Simulable &parent, const rapidxml::xml_node< char > *root)
mrpt::Clock::time_point get_simul_timestamp() const
Definition: World.h:118
static void RegisterSensorOriginViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
Definition: SensorBase.cpp:76
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCustomVisual_
Definition: VisualObject.h:75
Simulable & vehicle_
The vehicle this sensor is attached to.
Definition: SensorBase.h:74
virtual void simul_pre_timestep(const TSimulContext &context) override
void freeOpenGLResources() override
void reportNewObservation(const std::shared_ptr< mrpt::obs::CObservation > &obs, const TSimulContext &context)
Definition: SensorBase.cpp:160
mrpt::obs::CObservation3DRangeScan sensor_params_
std::string name_
Definition: Simulable.h:120
std::optional< TSimulContext > has_to_render_
virtual void simul_post_timestep(const TSimulContext &context)
Definition: Simulable.cpp:59
bool sense_rgb_
Simulate the RGB sensor part.
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
Definition: SensorBase.cpp:249
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
mrpt::system::CTimeLogger & getTimeLogger()
Definition: World.h:320
void simulateOn3DScene(mrpt::opengl::COpenGLScene &gl_scene) override
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_
mrpt::obs::CObservation3DRangeScan::Ptr last_obs2gui_
void mark_as_pending_running_sensors_on_3D_scene()
Definition: World.h:213
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_frustum_
void make_sure_we_have_a_name(const std::string &prefix)
Assign a sensible default name/sensor label if none is provided:
Definition: SensorBase.cpp:271
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