LaserScanner.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/COpenGLScene.h>
12 #include <mrpt/opengl/stock_objects.h>
13 #include <mrpt/random.h>
14 #include <mrpt/version.h>
16 #include <mvsim/VehicleBase.h>
17 #include <mvsim/World.h>
19 
20 #include "xml_utils.h"
21 
22 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
23 #include <mvsim/mvsim-msgs/ObservationLidar2D.pb.h>
24 #endif
25 
26 using namespace mvsim;
27 using namespace rapidxml;
28 
29 int z_order_cnt = 0;
30 
32  Simulable& parent, const rapidxml::xml_node<char>* root)
33  : SensorBase(parent), z_order_(++z_order_cnt)
34 {
36 }
37 
39 
41 {
42  gui_uptodate_ = false;
43 
46 
47  // Other scalar params:
48  int nRays = 181;
49  double fov_deg = 180;
50  scan_model_.sensorPose.z() = 0.05;
51 
52  TParameterDefinitions params;
53  params["fov_degrees"] = TParamEntry("%lf", &fov_deg);
54  params["nrays"] = TParamEntry("%i", &nRays);
55  params["pose"] = TParamEntry("%pose2d_ptr3d", &scan_model_.sensorPose);
56  params["pose_3d"] = TParamEntry("%pose3d", &scan_model_.sensorPose);
57  params["height"] = TParamEntry("%lf", &scan_model_.sensorPose.z());
58  params["range_std_noise"] = TParamEntry("%lf", &rangeStdNoise_);
59  params["max_range"] = TParamEntry("%f", &scan_model_.maxRange);
60  params["angle_std_noise_deg"] = TParamEntry("%lf_deg", &angleStdNoise_);
61  params["sensor_period"] = TParamEntry("%lf", &sensor_period_);
62  params["bodies_visible"] = TParamEntry("%bool", &see_fixtures_);
63 
64  params["viz_pointSize"] = TParamEntry("%f", &viz_pointSize_);
65  params["viz_visiblePlane"] = TParamEntry("%bool", &viz_visiblePlane_);
66  params["viz_visibleLines"] = TParamEntry("%bool", &viz_visibleLines_);
67  params["viz_visiblePoints"] = TParamEntry("%bool", &viz_visiblePoints_);
68 
69  params["viz_pointsColor"] = TParamEntry("%color", &viz_pointsColor_);
70  params["viz_planeColor"] = TParamEntry("%color", &viz_planeColor_);
71 
72  params["raytrace_3d"] = TParamEntry("%bool", &raytrace_3d_);
73  params["ignore_parent_body"] = TParamEntry("%bool", &ignore_parent_body_);
74 
75  // Parse XML params:
77 
78  // Pass params to the scan2D obj:
79  scan_model_.aperture = mrpt::DEG2RAD(fov_deg);
80  scan_model_.resizeScan(nRays);
81  scan_model_.stdError = rangeStdNoise_;
82 
83  scan_model_.sensorLabel = name_;
84 }
85 
87  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
88  [[maybe_unused]] const mrpt::optional_ref<mrpt::opengl::COpenGLScene>&
89  physical,
90  [[maybe_unused]] bool childrenOnly)
91 {
92  using namespace std::string_literals;
93 
94  mrpt::opengl::CSetOfObjects::Ptr glVizSensors;
95  if (viz)
96  {
97  glVizSensors = std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
98  viz->get().getByName("group_sensors_viz"));
99  if (!glVizSensors) return; // may happen during shutdown
100  }
101 
102  // 1st time?
103  if (!gl_scan_ && glVizSensors)
104  {
105  gl_scan_ = mrpt::opengl::CPlanarLaserScan::Create();
106 
107  gl_scan_->enablePoints(viz_visiblePoints_);
108  gl_scan_->setPointSize(viz_pointSize_);
109  const mrpt::img::TColorf ptsCol(viz_pointsColor_);
110  gl_scan_->setPointsColor(ptsCol.R, ptsCol.G, ptsCol.B, ptsCol.A);
111 
112  gl_scan_->enableSurface(viz_visiblePlane_);
113  const mrpt::img::TColorf planeCol(viz_planeColor_);
114  gl_scan_->setSurfaceColor(
115  planeCol.R, planeCol.G, planeCol.B, planeCol.A);
116 
117  gl_scan_->enableLine(viz_visibleLines_);
118 
119  gl_scan_->setLocalRepresentativePoint({0, 0, 0.10f});
120  gl_scan_->setName(
121  "glScan veh:"s + vehicle_.getName() + " sensor:"s + this->name_);
122 
123  glVizSensors->insert(gl_scan_);
124  }
125  if (!gl_sensor_origin_ && viz)
126  {
127  gl_sensor_origin_ = mrpt::opengl::CSetOfObjects::Create();
128 #if MRPT_VERSION >= 0x270
129  gl_sensor_origin_->castShadows(false);
130 #endif
132  mrpt::opengl::stock_objects::CornerXYZSimple(0.15f);
133 
135 
136  gl_sensor_origin_->setVisibility(false);
137  viz->get().insert(gl_sensor_origin_);
139  }
140  if (!gl_sensor_fov_ && viz)
141  {
142  gl_sensor_fov_ = mrpt::opengl::CSetOfObjects::Create();
143 #if MRPT_VERSION >= 0x270
144  gl_sensor_fov_->castShadows(false);
145 #endif
146 
147  auto fovScan = mrpt::opengl::CPlanarLaserScan::Create();
148  fovScan->enablePoints(false);
149  fovScan->enableSurface(true);
150 
151  mrpt::obs::CObservation2DRangeScan s = scan_model_;
152  const float f = 0.30f;
153  for (size_t i = 0; i < s.getScanSize(); i++)
154  {
155  s.setScanRange(i, f);
156  s.setScanRangeValidity(i, true);
157  }
158  fovScan->setScan(s);
159 
160  gl_sensor_fov_->insert(fovScan);
161 
162  gl_sensor_fov_->setVisibility(false);
163  viz->get().insert(gl_sensor_fov_);
165  }
166 
167  if (!gui_uptodate_ && glVizSensors->isVisible())
168  {
169  {
170  std::lock_guard<std::mutex> csl(last_scan_cs_);
171  if (last_scan2gui_)
172  {
173  gl_scan_->setScan(*last_scan2gui_);
174  gl_sensor_origin_corner_->setPose(last_scan2gui_->sensorPose);
175 
176  last_scan2gui_.reset();
177  }
178  }
179  gui_uptodate_ = true;
180  }
181 
182  const mrpt::poses::CPose2D& p = vehicle_.getCPose2D();
183  const double z_incrs = 1e-3; // for z_order_
184  const double z_offset = 1e-3;
185 
186  if (gl_scan_)
187  gl_scan_->setPose(mrpt::poses::CPose3D(
188  p.x(), p.y(), z_offset + z_incrs * z_order_, p.phi(), 0.0, 0.0));
189 
190  if (gl_sensor_fov_) gl_sensor_fov_->setPose(p);
191 
192  if (gl_sensor_origin_) gl_sensor_origin_->setPose(p);
193 
194  if (glCustomVisual_) glCustomVisual_->setPose(p + scan_model_.sensorPose);
195 }
196 
198  [[maybe_unused]] const TSimulContext& context)
199 {
200 }
201 
202 // Simulate sensor AFTER timestep, with the updated vehicle dynamical state:
204 {
206 
208  {
209  if (raytrace_3d_)
210  {
211  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
212 
213  // Will run upon next async call of simulateOn3DScene()
214  if (has_to_render_.has_value())
215  {
216  world_->logFmt(
217  mrpt::system::LVL_WARN,
218  "Time for a new sample came without still simulating the "
219  "last one (!) for simul_time=%.03f s.",
220  has_to_render_->simul_time);
221  }
222 
223  has_to_render_ = context;
225  }
226  else
227  {
228  // 2D mode:
230  }
231  }
232 }
233 
235 {
236  using mrpt::maps::COccupancyGridMap2D;
237  using mrpt::obs::CObservation2DRangeScan;
238 
239  auto tle =
240  mrpt::system::CTimeLoggerEntry(world_->getTimeLogger(), "LaserScanner");
241 
242  // Create an array of scans, each reflecting ranges to one kind of world
243  // objects.
244  // Finally, we'll take the shortest range in each direction:
245  std::list<CObservation2DRangeScan> lstScans;
246 
247  const size_t nRays = scan_model_.getScanSize();
248  const double maxRange = scan_model_.maxRange;
249 
250  // Get pose of the robot:
251  const mrpt::poses::CPose2D vehPose = vehicle_.getCPose2D();
252 
253  // grid maps:
254  // -------------
255  world_->getTimeLogger().enter("LaserScanner.scan.1.gridmap");
256 
258 
259  for (const auto& element : elements)
260  {
261  // If not a grid map, ignore:
262  const OccupancyGridMap* grid =
263  dynamic_cast<const OccupancyGridMap*>(element.get());
264  if (!grid) continue;
265  const COccupancyGridMap2D& occGrid = grid->getOccGrid();
266 
267  // Create new scan:
268  lstScans.emplace_back(scan_model_);
269  CObservation2DRangeScan& scan = lstScans.back();
270 
271  // Ray tracing over the gridmap:
272  occGrid.laserScanSimulator(
273  scan, vehPose, 0.5f, scan_model_.getScanSize(), rangeStdNoise_, 1,
275  }
276  world_->getTimeLogger().leave("LaserScanner.scan.1.gridmap");
277 
278  // ray trace on Box2D polygons:
279  // ------------------------------
280  world_->getTimeLogger().enter("LaserScanner.scan.2.polygons");
281  {
282  // Create new scan:
283  lstScans.push_back(CObservation2DRangeScan(scan_model_));
284  CObservation2DRangeScan& scan = lstScans.back();
285 
286  // Avoid the lidar seeing the vehicle owns shape:
287  std::map<b2Fixture*, uintptr_t> orgUserData;
288 
289  auto makeFixtureInvisible = [&](b2Fixture* f) {
290  if (!f) return;
291  orgUserData[f] = f->GetUserData().pointer;
292  f->GetUserData().pointer = INVISIBLE_FIXTURE_USER_DATA;
293  };
294  auto undoInvisibleFixtures = [&]() {
295  for (auto& kv : orgUserData)
296  kv.first->GetUserData().pointer = kv.second;
297  };
298 
299  if (auto v = dynamic_cast<VehicleBase*>(&vehicle_); v)
300  {
301  makeFixtureInvisible(v->get_fixture_chassis());
302  for (auto& f : v->get_fixture_wheels()) makeFixtureInvisible(f);
303  }
304 
305  // Do Box2D raycasting stuff:
306  // ------------------------------
307  // This callback finds the closest hit. Polygon 0 is filtered.
309  {
310  public:
311  RayCastClosestCallback() = default;
312 
313  float ReportFixture(
314  b2Fixture* fixture, const b2Vec2& point, const b2Vec2& normal,
315  float fraction) override
316  {
317  if (!see_fixtures_ || fixture->GetUserData().pointer ==
319  {
320  // By returning -1, we instruct the calling code to ignore
321  // this fixture and
322  // continue the ray-cast to the next fixture.
323  return -1.0f;
324  }
325 
326  hit_ = true;
327  point_ = point;
328  normal_ = normal;
329  // By returning the current fraction, we instruct the calling
330  // code to clip the ray and
331  // continue the ray-cast to the next fixture. WARNING: do not
332  // assume that fixtures
333  // are reported in order. However, by clipping, we can always
334  // get the closest fixture.
335  return fraction;
336  }
337 
338  bool see_fixtures_ = true;
339  bool hit_ = false;
340  b2Vec2 point_{0, 0};
341  b2Vec2 normal_{0, 0};
342  };
343 
344  const mrpt::poses::CPose2D sensorPose =
345  vehPose + mrpt::poses::CPose2D(scan.sensorPose);
346  const b2Vec2 sensorPt = b2Vec2(sensorPose.x(), sensorPose.y());
347 
348  RayCastClosestCallback callback;
349  callback.see_fixtures_ = see_fixtures_;
350 
351  // Scan size:
352  ASSERT_(nRays >= 2);
353  scan.resizeScanAndAssign(nRays, maxRange, false);
354  double A =
355  sensorPose.phi() + (scan.rightToLeft ? -0.5 : +0.5) * scan.aperture;
356  const double AA =
357  (scan.rightToLeft ? 1.0 : -1.0) * (scan.aperture / (nRays - 1));
358 
359  // Each thread must create its own rng:
360  thread_local mrpt::random::CRandomGenerator rnd;
361 
362  for (size_t i = 0; i < nRays; i++, A += AA)
363  {
364  const b2Vec2 endPt = b2Vec2(
365  sensorPt.x + cos(A) * maxRange, sensorPt.y + sin(A) * maxRange);
366 
367  callback.hit_ = false;
368  world_->getBox2DWorld()->RayCast(&callback, sensorPt, endPt);
369  scan.setScanRangeValidity(i, callback.hit_);
370 
371  float range = 0;
372  if (callback.hit_)
373  {
374  // Hit:
375  range = std::sqrt(
376  mrpt::square(callback.point_.x - sensorPt.x) +
377  mrpt::square(callback.point_.y - sensorPt.y));
378  range += rnd.drawGaussian1D_normalized() * rangeStdNoise_;
379  }
380  else
381  {
382  // Miss:
383  range = maxRange;
384  }
385  scan.setScanRange(i, range);
386  } // end for (raycast scan)
387 
388  undoInvisibleFixtures();
389  }
390  world_->getTimeLogger().leave("LaserScanner.scan.2.polygons");
391 
392  // Summarize all scans in one single scan:
393  // ----------------------------------------
394  world_->getTimeLogger().enter("LaserScanner.scan.3.merge");
395 
396  auto lastScan = CObservation2DRangeScan::Create(scan_model_);
397 
398  lastScan->timestamp = world_->get_simul_timestamp();
399  lastScan->sensorLabel = name_;
400 
401  lastScan->resizeScanAndAssign(nRays, maxRange, false);
402 
403  for (const auto& scan : lstScans)
404  {
405  for (size_t i = 0; i < nRays; i++)
406  {
407  if (scan.getScanRangeValidity(i))
408  {
409  lastScan->setScanRange(
410  i,
411  std::min(lastScan->getScanRange(i), scan.getScanRange(i)));
412  lastScan->setScanRangeValidity(i, true);
413  }
414  }
415  }
416  world_->getTimeLogger().leave("LaserScanner.scan.3.merge");
417 
418  {
419  std::lock_guard<std::mutex> csl(last_scan_cs_);
420  last_scan_ = std::move(lastScan);
422  }
423 
424  // publish as generic Protobuf (mrpt serialized) object:
426 
427  // Publish custom 2d-lidar observation type too:
429 
430  gui_uptodate_ = false;
431 }
432 
434 {
435  // Free fbo:
436  fbo_renderer_depth_.reset();
437 }
438 
439 void LaserScanner::simulateOn3DScene(mrpt::opengl::COpenGLScene& world3DScene)
440 {
441  using namespace mrpt; // _deg
442 
443  {
444  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
445  if (!has_to_render_.has_value()) return;
446  }
447 
448  auto tleWhole = mrpt::system::CTimeLoggerEntry(
449  world_->getTimeLogger(), "sensor.2Dlidar");
450 
451  auto tle1 = mrpt::system::CTimeLoggerEntry(
452  world_->getTimeLogger(), "sensor.2Dlidar.acqGuiMtx");
453 
454  tle1.stop();
455 
456  if (glCustomVisual_) glCustomVisual_->setVisibility(false);
457 
458  // Start making a copy of the pattern observation:
459  auto curObs = mrpt::obs::CObservation2DRangeScan::Create(scan_model_);
460 
461  const size_t nRays = scan_model_.getScanSize();
462  const double maxRange = scan_model_.maxRange;
463 
464  curObs->timestamp = world_->get_simul_timestamp();
465  curObs->sensorLabel = name_;
466 
467  curObs->resizeScanAndAssign(nRays, maxRange, false);
468 
469  // Create FBO on first use, now that we are here at the GUI / OpenGL thread.
470  constexpr int FBO_NROWS = 1;
471  constexpr int FBO_NCOLS = 500;
472  constexpr double camModel_FOV = 150.0_deg;
473  mrpt::img::TCamera camModel;
474  camModel.ncols = FBO_NCOLS;
475  camModel.nrows = FBO_NROWS;
476  camModel.cx(camModel.ncols / 2.0);
477  camModel.cy(camModel.nrows / 2.0);
478  camModel.fx(camModel.cx() / tan(camModel_FOV * 0.5)); // tan(FOV/2)=cx/fx
479  camModel.fy(camModel.fx());
480 
481  if (!fbo_renderer_depth_)
482  {
483  mrpt::opengl::CFBORender::Parameters p;
484  p.width = FBO_NCOLS;
485  p.height = FBO_NROWS;
486  p.create_EGL_context = world()->sensor_has_to_create_egl_context();
487 
488  fbo_renderer_depth_ = std::make_shared<mrpt::opengl::CFBORender>(p);
489  }
490 
491  auto viewport = world3DScene.getViewport();
492 
493  auto& cam = fbo_renderer_depth_->getCamera(world3DScene);
494 
495  const auto fixedAxisConventionRot =
496  mrpt::poses::CPose3D(0, 0, 0, -90.0_deg, 0.0_deg, -90.0_deg);
497 
498  const auto vehiclePose = mrpt::poses::CPose3D(vehicle_.getPose());
499 
500  // ----------------------------------------------------------
501  // Decompose the 2D lidar FOV into "n" depth camera images,
502  // of camModel_FOV each.
503  // ----------------------------------------------------------
504  const auto firstAngle = curObs->getScanAngle(0); // wrt sensorPose
505  const auto lastAngle = curObs->getScanAngle(curObs->getScanSize() - 1);
506  const bool scanIsCW = (lastAngle > firstAngle);
507  ASSERT_NEAR_(std::abs(lastAngle - firstAngle), curObs->aperture, 1e-3);
508 
509  const unsigned int numRenders =
510  std::ceil((curObs->aperture / camModel_FOV) - 1e-3);
511  const auto numRaysPerRender = mrpt::round(
512  nRays * std::min<double>(1.0, (camModel_FOV / curObs->aperture)));
513 
514  ASSERT_(numRaysPerRender > 0);
515 
516  // Precomputed LUT of bearings to pixel coordinates:
517  // cx - u
518  // tan(bearing) = --------------
519  // fx
520  //
521  if (angleIdx2pixelIdx_.empty())
522  {
523  angleIdx2pixelIdx_.resize(numRaysPerRender);
524  angleIdx2secant_.resize(numRaysPerRender);
525 
526  for (int i = 0; i < numRaysPerRender; i++)
527  {
528  const auto ang = (scanIsCW ? -1 : 1) *
529  (camModel_FOV * 0.5 -
530  i * camModel_FOV / (numRaysPerRender - 1));
531 
532  const auto pixelIdx = mrpt::saturate_val<int>(
533  mrpt::round(camModel.cx() - camModel.fx() * std::tan(ang)), 0,
534  camModel.ncols - 1);
535 
536  angleIdx2pixelIdx_.at(i) = pixelIdx;
537  angleIdx2secant_.at(i) = 1.0f / std::cos(ang);
538  }
539  }
540  else
541  {
542  // sanity check:
543  ASSERT_EQUAL_(angleIdx2pixelIdx_.size(), numRaysPerRender);
544  ASSERT_EQUAL_(angleIdx2secant_.size(), numRaysPerRender);
545  }
546 
547  // ----------------------------------------------------------
548  // "DEPTH camera" to generate lidar readings:
549  // ----------------------------------------------------------
550  cam.set6DOFMode(true);
551  cam.setProjectiveFromPinhole(camModel);
552 
553  // Disable rendering of shadows for this sensor:
554 #if MRPT_VERSION >= 0x270
555  const bool wasShadowEnabled = viewport->isShadowCastingEnabled();
556  viewport->enableShadowCasting(false);
557 #endif
558 
559  viewport->setViewportClipDistances(0.01, curObs->maxRange);
560  mrpt::math::CMatrixFloat depthImage;
561 
562  // make owner's own body invisible?
563  auto visVeh = dynamic_cast<VisualObject*>(&vehicle_);
564  auto veh = dynamic_cast<VehicleBase*>(&vehicle_);
565  bool formerVisVehState = true;
567  {
568  if (visVeh)
569  {
570  formerVisVehState = visVeh->customVisualVisible();
571  visVeh->customVisualVisible(false);
572  }
573  if (veh) veh->chassisAndWheelsVisible(false);
574  }
575 
576  for (size_t renderIdx = 0; renderIdx < numRenders; renderIdx++)
577  {
578  const double thisRenderMidAngle =
579  firstAngle + (camModel_FOV / 2.0 + camModel_FOV * renderIdx) *
580  (scanIsCW ? 1 : -1);
581 
582  const auto depthSensorPose = vehiclePose + curObs->sensorPose +
583  mrpt::poses::CPose3D::FromYawPitchRoll(
584  thisRenderMidAngle, 0.0, 0.0) +
585  fixedAxisConventionRot;
586 
587  // Camera pose: vehicle + relativePoseOnVehicle:
588  // Note: relativePoseOnVehicle should be (y,p,r)=(90deg,0,90deg) to make
589  // the camera to look forward:
590  cam.setPose(depthSensorPose);
591 
592  auto tleRender = mrpt::system::CTimeLoggerEntry(
593  world_->getTimeLogger(), "sensor.2Dlidar.renderSubScan");
594 
595  fbo_renderer_depth_->render_depth(world3DScene, depthImage);
596 
597  tleRender.stop();
598 
599  // Add random noise:
600  if (rangeStdNoise_ > 0)
601  {
602  auto tleStore = mrpt::system::CTimeLoggerEntry(
603  world_->getTimeLogger(), "sensor.2Dlidar.noise");
604 
605  // Each thread must create its own rng:
606  thread_local mrpt::random::CRandomGenerator rng;
607 
608  float* d = depthImage.data();
609  const size_t N = depthImage.size();
610  for (size_t i = 0; i < N; i++)
611  {
612  if (d[i] == 0) continue; // it was an invalid ray return.
613 
614  const float dNoisy =
615  d[i] + rng.drawGaussian1D(0, rangeStdNoise_);
616 
617  if (dNoisy < 0 || dNoisy > curObs->maxRange) continue;
618 
619  d[i] = dNoisy;
620  }
621  }
622 
623  auto tleStore = mrpt::system::CTimeLoggerEntry(
624  world_->getTimeLogger(), "sensor.2Dlidar.storeObs");
625 
626  // Convert depth into range and store into scan observation:
627  for (int i = 0; i < numRaysPerRender; i++)
628  {
629  const auto scanRayIdx = numRaysPerRender * renderIdx + i;
630  // done with full scan range?
631  if (scanRayIdx >= curObs->getScanSize()) break;
632 
633  const auto u = angleIdx2pixelIdx_.at(i);
634 
635  const float d = depthImage(0, u);
636  const float range = d * angleIdx2secant_.at(i);
637 
638  if (range <= 0 || range >= curObs->maxRange) continue; // invalid
639 
640  curObs->setScanRange(scanRayIdx, range);
641  curObs->setScanRangeValidity(scanRayIdx, true);
642  }
643  tleStore.stop();
644  }
645 
647  {
648  if (visVeh) visVeh->customVisualVisible(formerVisVehState);
649  if (veh) veh->chassisAndWheelsVisible(formerVisVehState);
650  }
651 
652 #if MRPT_VERSION >= 0x270
653  viewport->enableShadowCasting(wasShadowEnabled);
654 #endif
655 
656  // Store generated obs:
657  {
658  auto tle3 = mrpt::system::CTimeLoggerEntry(
659  world_->getTimeLogger(), "sensor.2Dlidar.acqObsMtx");
660 
661  std::lock_guard<std::mutex> csl(last_scan_cs_);
662  last_scan_ = std::move(curObs);
664  }
665 
666  {
667  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
668 
669  auto tlePub = mrpt::system::CTimeLoggerEntry(
670  world_->getTimeLogger(), "sensor.2Dlidar.report");
671 
672  // publish as generic Protobuf (mrpt serialized) object:
674 
675  // Publish custom 2d-lidar observation type too:
677 
678  tlePub.stop();
679 
680  if (glCustomVisual_) glCustomVisual_->setVisibility(true);
681 
682  gui_uptodate_ = false;
683 
684  has_to_render_.reset();
685  }
686 }
687 
689 {
690  using namespace std::string_literals;
691 
693 
694 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
695  // Topic:
696  if (!publishTopic_.empty())
697  c.advertiseTopic<mvsim_msgs::ObservationLidar2D>(
698  publishTopic_ + "_scan"s);
699 #endif
700 }
d
bool sensor_has_to_create_egl_context()
Definition: World.cpp:397
std::string publishTopic_
Definition: SensorBase.h:89
World * world()
Definition: SensorBase.h:76
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
Definition: LaserScanner.h:93
constexpr uintptr_t INVISIBLE_FIXTURE_USER_DATA
Used to signal a Box2D fixture as "invisible" to sensors.
Definition: basic_types.h:64
std::vector< size_t > angleIdx2pixelIdx_
Definition: LaserScanner.h:102
std::map< std::string, TParamEntry > TParameterDefinitions
const WorldElementList & getListOfWorldElements() const
Definition: World.h:307
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
mrpt::img::TColor viz_planeColor_
Definition: LaserScanner.h:77
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_
Definition: LaserScanner.h:95
float x
Definition: b2_math.h:128
float y
Definition: b2_math.h:128
static void RegisterSensorFOVViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
Definition: SensorBase.cpp:71
XmlRpcServer s
std::mutex last_scan_cs_
Definition: LaserScanner.h:83
mrpt::obs::CObservation2DRangeScan::Ptr last_scan_
Definition: LaserScanner.h:85
std::mutex has_to_render_mtx_
Definition: LaserScanner.h:98
std::unique_ptr< b2World > & getBox2DWorld()
Definition: World.h:297
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
b2FixtureUserData & GetUserData()
Definition: b2_fixture.h:278
const mrpt::maps::COccupancyGridMap2D & getOccGrid() const
A 2D column vector.
Definition: b2_math.h:41
mrpt::Clock::time_point get_simul_timestamp() const
Definition: World.h:118
mrpt::obs::CObservation2DRangeScan::Ptr last_scan2gui_
Definition: LaserScanner.h:86
mrpt::obs::CObservation2DRangeScan scan_model_
Definition: LaserScanner.h:81
static void RegisterSensorOriginViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
Definition: SensorBase.cpp:76
void freeOpenGLResources() override
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCustomVisual_
Definition: VisualObject.h:75
Simulable & vehicle_
The vehicle this sensor is attached to.
Definition: SensorBase.h:74
void registerOnServer(mvsim::Client &c) override
Definition: SensorBase.cpp:237
int z_order_
to help rendering multiple scans
Definition: LaserScanner.h:58
void internal_simulate_lidar_2d_mode(const TSimulContext &context)
mrpt::poses::CPose2D getCPose2D() const
Alternative to getPose()
Definition: Simulable.cpp:125
virtual void internalGuiUpdate(const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
void reportNewObservation(const std::shared_ptr< mrpt::obs::CObservation > &obs, const TSimulContext &context)
Definition: SensorBase.cpp:160
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_depth_
Definition: LaserScanner.h:100
std::string name_
Definition: Simulable.h:120
virtual void simul_pre_timestep(const TSimulContext &context) override
uintptr_t pointer
For legacy compatibility.
Definition: b2_settings.h:78
virtual void simul_post_timestep(const TSimulContext &context)
Definition: Simulable.cpp:59
const std::string & getName() const
Definition: Simulable.h:92
double sensor_period_
Definition: SensorBase.h:80
virtual void simul_post_timestep(const TSimulContext &context) override
void simulateOn3DScene(mrpt::opengl::COpenGLScene &gl_scene) override
void registerOnServer(mvsim::Client &c) override
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
Definition: SensorBase.cpp:249
mrpt::system::CTimeLogger & getTimeLogger()
Definition: World.h:320
void advertiseTopic(const std::string &topicName)
Definition: Client.h:187
mrpt::opengl::CPlanarLaserScan::Ptr gl_scan_
Definition: LaserScanner.h:92
mrpt::img::TColor viz_pointsColor_
Definition: LaserScanner.h:76
static int min(int n1, int n2)
Definition: wl_init.c:42
int z_order_cnt
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
std::list< WorldElementBase::Ptr > WorldElementList
Definition: World.h:284
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
void mark_as_pending_running_sensors_on_3D_scene()
Definition: World.h:213
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
void reportNewObservation_lidar_2d(const std::shared_ptr< mrpt::obs::CObservation2DRangeScan > &obs, const TSimulContext &context)
Definition: SensorBase.cpp:201
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_
Definition: LaserScanner.h:93
std::vector< float > angleIdx2secant_
Definition: LaserScanner.h:103
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)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
LaserScanner(Simulable &parent, const rapidxml::xml_node< char > *root)
std::optional< TSimulContext > has_to_render_
Definition: LaserScanner.h:97


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