Lidar3D.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/maps/CSimplePointsMap.h>
12 #include <mrpt/opengl/COpenGLScene.h>
13 #include <mrpt/opengl/stock_objects.h>
14 #include <mrpt/random.h>
15 #include <mrpt/version.h>
16 #include <mvsim/Sensors/Lidar3D.h>
17 #include <mvsim/VehicleBase.h>
18 #include <mvsim/World.h>
20 
21 #if MRPT_VERSION >= 0x270
22 #include <mrpt/opengl/OpenGLDepth2LinearLUTs.h>
23 #endif
24 
25 #include "xml_utils.h"
26 
27 using namespace mvsim;
28 using namespace rapidxml;
29 
30 MRPT_TODO("Also store obs as CObservationRotatingScan?")
31 
32 Lidar3D::Lidar3D(Simulable& parent, const rapidxml::xml_node<char>* root)
33  : SensorBase(parent)
34 {
36 }
37 
39 
41 {
42  gui_uptodate_ = false;
43 
46 
47  // Other scalar params:
48  TParameterDefinitions params;
49  params["pose_3d"] = TParamEntry("%pose3d", &sensorPoseOnVeh_);
50  params["range_std_noise"] = TParamEntry("%lf", &rangeStdNoise_);
51  params["sensor_period"] = TParamEntry("%lf", &sensor_period_);
52  params["min_range"] = TParamEntry("%f", &minRange_);
53  params["max_range"] = TParamEntry("%f", &maxRange_);
54  params["viz_pointSize"] = TParamEntry("%f", &viz_pointSize_);
55  params["ignore_parent_body"] = TParamEntry("%bool", &ignore_parent_body_);
56 
57  params["vert_fov_degrees"] = TParamEntry("%lf_deg", &vertical_fov_);
58  params["vert_nrays"] = TParamEntry("%i", &vertNumRays_);
59  params["horz_nrays"] = TParamEntry("%i", &horzNumRays_);
60 
61  params["fbo_nrows"] = TParamEntry("%i", &fbo_nrows_);
62 
63  // Parse XML params:
64  parse_xmlnode_children_as_param(*root, params, varValues_);
65 }
66 
68  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
69  [[maybe_unused]] const mrpt::optional_ref<mrpt::opengl::COpenGLScene>&
70  physical,
71  [[maybe_unused]] bool childrenOnly)
72 {
73  mrpt::opengl::CSetOfObjects::Ptr glVizSensors;
74  if (viz)
75  {
76  glVizSensors = std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
77  viz->get().getByName("group_sensors_viz"));
78  if (!glVizSensors) return; // may happen during shutdown
79  }
80 
81  // 1st time?
82  if (!glPoints_ && glVizSensors)
83  {
84  glPoints_ = mrpt::opengl::CPointCloudColoured::Create();
85  glPoints_->setPointSize(viz_pointSize_);
86  glPoints_->setLocalRepresentativePoint({0, 0, 0.10f});
87 
88  glVizSensors->insert(glPoints_);
89  }
90  if (!gl_sensor_origin_ && viz)
91  {
92  gl_sensor_origin_ = mrpt::opengl::CSetOfObjects::Create();
93 #if MRPT_VERSION >= 0x270
94  gl_sensor_origin_->castShadows(false);
95 #endif
96  gl_sensor_origin_corner_ =
97  mrpt::opengl::stock_objects::CornerXYZSimple(0.15f);
98 
99  gl_sensor_origin_->insert(gl_sensor_origin_corner_);
100 
101  gl_sensor_origin_->setVisibility(false);
102  viz->get().insert(gl_sensor_origin_);
103  SensorBase::RegisterSensorOriginViz(gl_sensor_origin_);
104  }
105  if (!gl_sensor_fov_ && viz)
106  {
107  gl_sensor_fov_ = mrpt::opengl::CSetOfObjects::Create();
108 
109  MRPT_TODO("render 3D lidar FOV");
110 #if 0
111  auto fovScan = mrpt::opengl::CPlanarLaserScan::Create();
112  gl_sensor_fov_->insert(fovScan);
113 #endif
114  gl_sensor_fov_->setVisibility(false);
115  viz->get().insert(gl_sensor_fov_);
116  SensorBase::RegisterSensorFOVViz(gl_sensor_fov_);
117  }
118 
119  if (!gui_uptodate_ && glVizSensors->isVisible())
120  {
121  {
122  std::lock_guard<std::mutex> csl(last_scan_cs_);
123  if (last_scan2gui_ && last_scan2gui_->pointcloud)
124  {
125  glPoints_->loadFromPointsMap(last_scan2gui_->pointcloud.get());
126  gl_sensor_origin_corner_->setPose(last_scan2gui_->sensorPose);
127 
128  last_scan2gui_.reset();
129  }
130  }
131  gui_uptodate_ = true;
132  }
133 
134  const mrpt::poses::CPose3D p = vehicle_.getCPose3D() + sensorPoseOnVeh_;
135 
136  if (glPoints_) glPoints_->setPose(p);
137  if (gl_sensor_fov_) gl_sensor_fov_->setPose(p);
138  if (gl_sensor_origin_) gl_sensor_origin_->setPose(p);
139  if (glCustomVisual_) glCustomVisual_->setPose(p);
140 }
141 
142 void Lidar3D::simul_pre_timestep([[maybe_unused]] const TSimulContext& context)
143 {
144 }
145 
146 // Simulate sensor AFTER timestep, with the updated vehicle dynamical state:
148 {
150 
152  {
153  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
154 
155  // Will run upon next async call of simulateOn3DScene()
156  if (has_to_render_.has_value())
157  {
158  world_->logFmt(
159  mrpt::system::LVL_WARN,
160  "Time for a new sample came without still simulating the "
161  "last one (!) for simul_time=%.03f s.",
162  has_to_render_->simul_time);
163  }
164 
165  has_to_render_ = context;
166  world_->mark_as_pending_running_sensors_on_3D_scene();
167  }
168 }
169 
171 {
172  // Free fbo:
173  fbo_renderer_depth_.reset();
174 }
175 
176 void Lidar3D::simulateOn3DScene(mrpt::opengl::COpenGLScene& world3DScene)
177 {
178  using namespace mrpt; // _deg
179 
180  {
181  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
182  if (!has_to_render_.has_value()) return;
183  }
184 
185  auto tleWhole = mrpt::system::CTimeLoggerEntry(
186  world_->getTimeLogger(), "sensor.3Dlidar");
187 
188  auto tle1 = mrpt::system::CTimeLoggerEntry(
189  world_->getTimeLogger(), "sensor.3Dlidar.acqGuiMtx");
190 
191  tle1.stop();
192 
193  // The sensor body must be made of transparent material! :-)
194  if (glCustomVisual_) glCustomVisual_->setVisibility(false);
195 
196  // Create empty observation:
197  auto curObs = mrpt::obs::CObservationPointCloud::Create();
198  curObs->sensorPose = sensorPoseOnVeh_;
199  curObs->timestamp = world_->get_simul_timestamp();
200  curObs->sensorLabel = name_;
201 
202  auto curPtsPtr = mrpt::maps::CSimplePointsMap::Create();
203  auto& curPts = *curPtsPtr;
204  curObs->pointcloud = curPtsPtr;
205 
206  // Create FBO on first use, now that we are here at the GUI / OpenGL thread.
207  constexpr double camModel_hFOV = 120.01_deg;
208  const int FBO_NROWS = fbo_nrows_;
209  // This FBO is for camModel_hFOV only:
210  const int FBO_NCOLS = horzNumRays_;
211 
212  // worst vFOV case: at each sub-scan render corner:
213  const double camModel_vFOV =
214  std::min(179.0_deg, 2.05 * atan2(1.0, 1.0 / cos(camModel_hFOV * 0.5)));
215 
216  mrpt::img::TCamera camModel;
217  camModel.ncols = FBO_NCOLS;
218  camModel.nrows = FBO_NROWS;
219  camModel.cx(camModel.ncols / 2.0);
220  camModel.cy(camModel.nrows / 2.0);
221  camModel.fx(camModel.cx() / tan(camModel_hFOV * 0.5)); // tan(FOV/2)=cx/fx
222  camModel.fy(camModel.cy() / tan(camModel_vFOV * 0.5));
223 
224  if (!fbo_renderer_depth_)
225  {
226  mrpt::opengl::CFBORender::Parameters p;
227  p.width = FBO_NCOLS;
228  p.height = FBO_NROWS;
229  p.create_EGL_context = world()->sensor_has_to_create_egl_context();
230 
231 #if MRPT_VERSION >= 0x270
232  // Do the log->linear conversion ourselves for this sensor, since only a
233  // few depth points are actually used.
234  p.raw_depth = true;
235 #endif
236 
237  fbo_renderer_depth_ = std::make_shared<mrpt::opengl::CFBORender>(p);
238  }
239 
240  const size_t nCols = horzNumRays_;
241  const size_t nRows = vertNumRays_;
242 
243  mrpt::math::CMatrixDouble rangeImage(nRows, nCols);
244  rangeImage.setZero(); // 0=invalid (no lidar return)
245 
246  auto viewport = world3DScene.getViewport();
247 
248  // Disable rendering of shadows for this sensor:
249 #if MRPT_VERSION >= 0x270
250  const bool wasShadowEnabled = viewport->isShadowCastingEnabled();
251  viewport->enableShadowCasting(false);
252 #endif
253 
254  auto& cam = fbo_renderer_depth_->getCamera(world3DScene);
255 
256  const auto fixedAxisConventionRot =
257  mrpt::poses::CPose3D(0, 0, 0, -90.0_deg, 0.0_deg, -90.0_deg);
258 
259  const auto vehiclePose = mrpt::poses::CPose3D(vehicle_.getPose());
260 
261  // ----------------------------------------------------------
262  // Decompose the horizontal lidar FOV into "n" depth images,
263  // of camModel_hFOV each.
264  // ----------------------------------------------------------
265  ASSERT_GT_(horzNumRays_, 1);
266  ASSERT_GT_(vertNumRays_, 1);
267 
268  constexpr bool scanIsCW = false;
269  constexpr double aperture = 2 * M_PI;
270 
271  const double firstAngle = -aperture * 0.5;
272 
273  const unsigned int numRenders =
274  std::ceil((aperture / camModel_hFOV) - 1e-3);
275  const auto numHorzRaysPerRender = mrpt::round(
276  horzNumRays_ * std::min<double>(1.0, (camModel_hFOV / aperture)));
277 
278  ASSERT_(numHorzRaysPerRender > 0);
279 
280  // Precomputed LUT of bearings to pixel coordinates:
281  // cx - u
282  // tan(horzBearing) = --------------
283  // fx
284  //
285  // cy - v
286  // tan(vertBearing) = -------------------------
287  // fy / cos(horzBearing)
288  //
289  if (lut_.empty())
290  {
291  lut_.resize(numHorzRaysPerRender);
292 
293  for (int i = 0; i < numHorzRaysPerRender; i++)
294  {
295  lut_[i].column.resize(nRows);
296 
297  const double horzAng =
298  (scanIsCW ? -1 : 1) *
299  (camModel_hFOV * 0.5 -
300  i * camModel_hFOV / (numHorzRaysPerRender - 1));
301 
302  const double cosHorzAng = std::cos(horzAng);
303 
304  const auto pixel_u = mrpt::saturate_val<int>(
305  mrpt::round(camModel.cx() - camModel.fx() * std::tan(horzAng)),
306  0, camModel.ncols - 1);
307 
308  for (size_t j = 0; j < nRows; j++)
309  {
310  auto& entry = lut_[i].column[j];
311 
312  const auto vertAng =
313  -vertical_fov_ * 0.5 + j * vertical_fov_ / (nRows - 1);
314 
315  const double cosVertAng = std::cos(vertAng);
316 
317  const auto pixel_v = mrpt::round(
318  camModel.cy() -
319  camModel.fy() * std::tan(vertAng) / cosHorzAng);
320 
321  // out of the simulated camera (should not happen?)
322  if (pixel_v < 0 || pixel_v >= static_cast<int>(camModel.nrows))
323  continue;
324 
325  entry.u = pixel_u;
326  entry.v = pixel_v;
327  entry.depth2range = 1.0f / (cosHorzAng * cosVertAng);
328  }
329  }
330  }
331  else
332  {
333  // check:
334  ASSERT_EQUAL_(lut_.size(), numHorzRaysPerRender);
335  ASSERT_EQUAL_(lut_.at(0).column.size(), nRows);
336  }
337 
338  // ----------------------------------------------------------
339  // "DEPTH camera" to generate lidar readings:
340  // ----------------------------------------------------------
341  cam.set6DOFMode(true);
342  cam.setProjectiveFromPinhole(camModel);
343 
344  viewport->setViewportClipDistances(minRange_, maxRange_);
345  mrpt::math::CMatrixFloat depthImage;
346 
347  // make owner's own body invisible?
348  auto visVeh = dynamic_cast<VisualObject*>(&vehicle_);
349  auto veh = dynamic_cast<VehicleBase*>(&vehicle_);
350  bool formerVisVehState = true;
351  if (ignore_parent_body_)
352  {
353  if (visVeh)
354  {
355  formerVisVehState = visVeh->customVisualVisible();
356  visVeh->customVisualVisible(false);
357  }
358  if (veh) veh->chassisAndWheelsVisible(false);
359  }
360 
361 #if MRPT_VERSION >= 0x270
362  // Do the log->linear conversion ourselves for this sensor,
363  // since only a few depth points are actually used:
364  constexpr int DEPTH_LOG2LIN_BITS = 18;
365  using depth_log2lin_t =
366  mrpt::opengl::OpenGLDepth2LinearLUTs<DEPTH_LOG2LIN_BITS>;
367  auto& depth_log2lin = depth_log2lin_t::Instance();
368  const auto& depth_log2lin_lut =
369  depth_log2lin.lut_from_zn_zf(minRange_, maxRange_);
370 
371 #endif
372 
373  for (size_t renderIdx = 0; renderIdx < numRenders; renderIdx++)
374  {
375  const double thisRenderMidAngle =
376  firstAngle + (camModel_hFOV / 2.0 + camModel_hFOV * renderIdx) *
377  (scanIsCW ? 1 : -1);
378 
379  const auto thisDepthSensorPoseWrtSensor =
380  mrpt::poses::CPose3D::FromYawPitchRoll(
381  thisRenderMidAngle, 0.0, 0.0) +
382  fixedAxisConventionRot;
383 
384  const auto thisDepthSensorPoseOnVeh =
385  curObs->sensorPose + thisDepthSensorPoseWrtSensor;
386 
387  const auto thisDepthSensorPose = vehiclePose + thisDepthSensorPoseOnVeh;
388 
389  // Camera pose: vehicle + relativePoseOnVehicle:
390  // Note: relativePoseOnVehicle should be (y,p,r)=(90deg,0,90deg)
391  // to make the camera to look forward:
392  cam.setPose(thisDepthSensorPose);
393 
394  auto tleRender = mrpt::system::CTimeLoggerEntry(
395  world_->getTimeLogger(), "sensor.3Dlidar.renderSubScan");
396 
397  fbo_renderer_depth_->render_depth(world3DScene, depthImage);
398 
399  tleRender.stop();
400 
401  // Add random noise:
402  // Each thread must create its own rng:
403  thread_local mrpt::random::CRandomGenerator rng;
404  thread_local std::vector<float> noiseSeq;
405  thread_local size_t noiseIdx = 0;
406  constexpr size_t noiseLen = 7823; // prime
407  if (rangeStdNoise_ > 0)
408  {
409  if (noiseSeq.empty())
410  {
411  noiseSeq.reserve(noiseLen);
412  for (size_t i = 0; i < noiseLen; i++)
413  noiseSeq.push_back(rng.drawGaussian1D(0.0, rangeStdNoise_));
414  }
415  }
416 
417  auto tleStore = mrpt::system::CTimeLoggerEntry(
418  world_->getTimeLogger(), "sensor.3Dlidar.storeObs");
419 
420  // Convert depth into range and store into polar range images:
421  for (int i = 0; i < numHorzRaysPerRender; i++)
422  {
423  const int iAbs = i + numHorzRaysPerRender * renderIdx;
424  if (iAbs >= rangeImage.cols())
425  continue; // we don't need this image part
426 
427  for (unsigned int j = 0; j < nRows; j++)
428  {
429  // LUT entry:
430  const auto& e = lut_.at(i).column.at(j);
431  const auto u = e.u;
432  const auto v = e.v;
433 
434  ASSERTDEB_LT_(u, depthImage.cols());
435  ASSERTDEB_LT_(v, depthImage.rows());
436 
437  // Depth:
438  float d = depthImage(v, u);
439 
440  // Linearize:
441 #if MRPT_VERSION >= 0x270
442  // Do the log->linear conversion ourselves for this sensor,
443  // since only a few depth points are actually used:
444 
445  // map d in [-1.0f,+1.0f] ==> real depth values:
446  d = depth_log2lin_lut
447  [(d + 1.0f) * (depth_log2lin_t::NUM_ENTRIES - 1) / 2];
448 #else
449  // "d" is already linear depth
450 #endif
451  // Add noise:
452  if (d != 0) // invalid range
453  {
454  const float dNoisy = d + noiseSeq[noiseIdx++];
455  if (noiseIdx >= noiseLen) noiseIdx = 0;
456 
457  if (dNoisy < 0 || dNoisy > maxRange_) continue;
458 
459  d = dNoisy;
460  }
461 
462  // un-project: depth -> range:
463  const float range = d * e.depth2range;
464 
465  if (range <= 0 || range >= maxRange_) continue; // invalid
466 
467  ASSERTDEB_LT_(j, rangeImage.rows());
468  ASSERTDEB_LT_(iAbs, rangeImage.cols());
469 
470  rangeImage(j, iAbs) = range;
471 
472  // add points:
473  const mrpt::math::TPoint3D pt_wrt_cam = {
474  d * (u - camModel.cx()) / camModel.fx(),
475  d * (v - camModel.cy()) / camModel.fy(), d};
476  curPts.insertPoint(
477  thisDepthSensorPoseWrtSensor.composePoint(pt_wrt_cam));
478  }
479  }
480  tleStore.stop();
481  }
482 
483  if (ignore_parent_body_)
484  {
485  if (visVeh) visVeh->customVisualVisible(formerVisVehState);
486  if (veh) veh->chassisAndWheelsVisible(formerVisVehState);
487  }
488 
489 #if MRPT_VERSION >= 0x270
490  viewport->enableShadowCasting(wasShadowEnabled);
491 #endif
492 
493  // Store generated obs:
494  {
495  auto tle3 = mrpt::system::CTimeLoggerEntry(
496  world_->getTimeLogger(), "sensor.3Dlidar.acqObsMtx");
497 
498  std::lock_guard<std::mutex> csl(last_scan_cs_);
499  last_scan_ = std::move(curObs);
500  last_scan2gui_ = last_scan_;
501  }
502 
503  {
504  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
505 
506  auto tlePub = mrpt::system::CTimeLoggerEntry(
507  world_->getTimeLogger(), "sensor.3Dlidar.report");
508 
509  SensorBase::reportNewObservation(last_scan_, *has_to_render_);
510 
511  tlePub.stop();
512 
513  if (glCustomVisual_) glCustomVisual_->setVisibility(true);
514 
515  gui_uptodate_ = false;
516 
517  has_to_render_.reset();
518  }
519 }
d
virtual ~Lidar3D()
Definition: Lidar3D.cpp:38
void simulateOn3DScene(mrpt::opengl::COpenGLScene &gl_scene) override
Definition: Lidar3D.cpp:176
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
static void RegisterSensorFOVViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
Definition: SensorBase.cpp:71
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
Definition: Lidar3D.cpp:40
bool should_simulate_sensor(const TSimulContext &context)
Definition: SensorBase.cpp:283
#define M_PI
void freeOpenGLResources() override
Definition: Lidar3D.cpp:170
static void RegisterSensorOriginViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
Definition: SensorBase.cpp:76
void reportNewObservation(const std::shared_ptr< mrpt::obs::CObservation > &obs, const TSimulContext &context)
Definition: SensorBase.cpp:160
virtual void simul_pre_timestep(const TSimulContext &context) override
Definition: Lidar3D.cpp:142
virtual void simul_post_timestep(const TSimulContext &context)
Definition: Simulable.cpp:59
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
Definition: SensorBase.cpp:249
A 3D LiDAR sensor, with 360 degrees horizontal fielf-of-view, and a configurable vertical FOV...
Definition: Lidar3D.h:29
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
static int min(int n1, int n2)
Definition: wl_init.c:42
virtual void internalGuiUpdate(const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
Definition: Lidar3D.cpp:67
virtual void simul_post_timestep(const TSimulContext &context) override
Definition: Lidar3D.cpp:147
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
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
void customVisualVisible(const bool visible)


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