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> 21 #if MRPT_VERSION >= 0x270 22 #include <mrpt/opengl/OpenGLDepth2LinearLUTs.h> 27 using namespace mvsim;
30 MRPT_TODO(
"Also store obs as CObservationRotatingScan?")
42 gui_uptodate_ =
false;
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_);
57 params[
"vert_fov_degrees"] =
TParamEntry(
"%lf_deg", &vertical_fov_);
58 params[
"vert_nrays"] =
TParamEntry(
"%i", &vertNumRays_);
59 params[
"horz_nrays"] =
TParamEntry(
"%i", &horzNumRays_);
61 params[
"fbo_nrows"] =
TParamEntry(
"%i", &fbo_nrows_);
68 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
69 [[maybe_unused]]
const mrpt::optional_ref<mrpt::opengl::COpenGLScene>&
71 [[maybe_unused]]
bool childrenOnly)
73 mrpt::opengl::CSetOfObjects::Ptr glVizSensors;
76 glVizSensors = std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
77 viz->get().getByName(
"group_sensors_viz"));
78 if (!glVizSensors)
return;
82 if (!glPoints_ && glVizSensors)
84 glPoints_ = mrpt::opengl::CPointCloudColoured::Create();
85 glPoints_->setPointSize(viz_pointSize_);
86 glPoints_->setLocalRepresentativePoint({0, 0, 0.10f});
88 glVizSensors->insert(glPoints_);
90 if (!gl_sensor_origin_ && viz)
92 gl_sensor_origin_ = mrpt::opengl::CSetOfObjects::Create();
93 #if MRPT_VERSION >= 0x270 94 gl_sensor_origin_->castShadows(
false);
96 gl_sensor_origin_corner_ =
97 mrpt::opengl::stock_objects::CornerXYZSimple(0.15
f);
99 gl_sensor_origin_->insert(gl_sensor_origin_corner_);
101 gl_sensor_origin_->setVisibility(
false);
102 viz->get().insert(gl_sensor_origin_);
105 if (!gl_sensor_fov_ && viz)
107 gl_sensor_fov_ = mrpt::opengl::CSetOfObjects::Create();
109 MRPT_TODO(
"render 3D lidar FOV");
111 auto fovScan = mrpt::opengl::CPlanarLaserScan::Create();
112 gl_sensor_fov_->insert(fovScan);
114 gl_sensor_fov_->setVisibility(
false);
115 viz->get().insert(gl_sensor_fov_);
119 if (!gui_uptodate_ && glVizSensors->isVisible())
122 std::lock_guard<std::mutex> csl(last_scan_cs_);
123 if (last_scan2gui_ && last_scan2gui_->pointcloud)
125 glPoints_->loadFromPointsMap(last_scan2gui_->pointcloud.get());
126 gl_sensor_origin_corner_->setPose(last_scan2gui_->sensorPose);
128 last_scan2gui_.reset();
131 gui_uptodate_ =
true;
134 const mrpt::poses::CPose3D p = vehicle_.getCPose3D() + sensorPoseOnVeh_;
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);
153 auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
156 if (has_to_render_.has_value())
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);
165 has_to_render_ = context;
166 world_->mark_as_pending_running_sensors_on_3D_scene();
173 fbo_renderer_depth_.reset();
178 using namespace mrpt;
181 auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
182 if (!has_to_render_.has_value())
return;
185 auto tleWhole = mrpt::system::CTimeLoggerEntry(
186 world_->getTimeLogger(),
"sensor.3Dlidar");
188 auto tle1 = mrpt::system::CTimeLoggerEntry(
189 world_->getTimeLogger(),
"sensor.3Dlidar.acqGuiMtx");
194 if (glCustomVisual_) glCustomVisual_->setVisibility(
false);
197 auto curObs = mrpt::obs::CObservationPointCloud::Create();
198 curObs->sensorPose = sensorPoseOnVeh_;
199 curObs->timestamp = world_->get_simul_timestamp();
200 curObs->sensorLabel = name_;
202 auto curPtsPtr = mrpt::maps::CSimplePointsMap::Create();
203 auto& curPts = *curPtsPtr;
204 curObs->pointcloud = curPtsPtr;
207 constexpr
double camModel_hFOV = 120.01_deg;
208 const int FBO_NROWS = fbo_nrows_;
210 const int FBO_NCOLS = horzNumRays_;
213 const double camModel_vFOV =
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));
222 camModel.fy(camModel.cy() /
tan(camModel_vFOV * 0.5));
224 if (!fbo_renderer_depth_)
226 mrpt::opengl::CFBORender::Parameters p;
228 p.height = FBO_NROWS;
229 p.create_EGL_context = world()->sensor_has_to_create_egl_context();
231 #if MRPT_VERSION >= 0x270 237 fbo_renderer_depth_ = std::make_shared<mrpt::opengl::CFBORender>(p);
240 const size_t nCols = horzNumRays_;
241 const size_t nRows = vertNumRays_;
243 mrpt::math::CMatrixDouble rangeImage(nRows, nCols);
244 rangeImage.setZero();
246 auto viewport = world3DScene.getViewport();
249 #if MRPT_VERSION >= 0x270 250 const bool wasShadowEnabled = viewport->isShadowCastingEnabled();
251 viewport->enableShadowCasting(
false);
254 auto& cam = fbo_renderer_depth_->getCamera(world3DScene);
256 const auto fixedAxisConventionRot =
257 mrpt::poses::CPose3D(0, 0, 0, -90.0_deg, 0.0_deg, -90.0_deg);
259 const auto vehiclePose = mrpt::poses::CPose3D(vehicle_.getPose());
265 ASSERT_GT_(horzNumRays_, 1);
266 ASSERT_GT_(vertNumRays_, 1);
268 constexpr
bool scanIsCW =
false;
269 constexpr
double aperture = 2 *
M_PI;
271 const double firstAngle = -aperture * 0.5;
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)));
278 ASSERT_(numHorzRaysPerRender > 0);
291 lut_.resize(numHorzRaysPerRender);
293 for (
int i = 0; i < numHorzRaysPerRender; i++)
295 lut_[i].column.resize(nRows);
297 const double horzAng =
298 (scanIsCW ? -1 : 1) *
299 (camModel_hFOV * 0.5 -
300 i * camModel_hFOV / (numHorzRaysPerRender - 1));
302 const double cosHorzAng = std::cos(horzAng);
304 const auto pixel_u = mrpt::saturate_val<int>(
305 mrpt::round(camModel.cx() - camModel.fx() * std::tan(horzAng)),
306 0, camModel.ncols - 1);
308 for (
size_t j = 0; j < nRows; j++)
310 auto& entry = lut_[i].column[j];
313 -vertical_fov_ * 0.5 + j * vertical_fov_ / (nRows - 1);
315 const double cosVertAng = std::cos(vertAng);
317 const auto pixel_v = mrpt::round(
319 camModel.fy() * std::tan(vertAng) / cosHorzAng);
322 if (pixel_v < 0 || pixel_v >= static_cast<int>(camModel.nrows))
327 entry.depth2range = 1.0f / (cosHorzAng * cosVertAng);
334 ASSERT_EQUAL_(lut_.size(), numHorzRaysPerRender);
335 ASSERT_EQUAL_(lut_.at(0).column.size(), nRows);
341 cam.set6DOFMode(
true);
342 cam.setProjectiveFromPinhole(camModel);
344 viewport->setViewportClipDistances(minRange_, maxRange_);
345 mrpt::math::CMatrixFloat depthImage;
350 bool formerVisVehState =
true;
351 if (ignore_parent_body_)
356 visVeh->customVisualVisible(
false);
358 if (veh) veh->chassisAndWheelsVisible(
false);
361 #if MRPT_VERSION >= 0x270 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_);
373 for (
size_t renderIdx = 0; renderIdx < numRenders; renderIdx++)
375 const double thisRenderMidAngle =
376 firstAngle + (camModel_hFOV / 2.0 + camModel_hFOV * renderIdx) *
379 const auto thisDepthSensorPoseWrtSensor =
380 mrpt::poses::CPose3D::FromYawPitchRoll(
381 thisRenderMidAngle, 0.0, 0.0) +
382 fixedAxisConventionRot;
384 const auto thisDepthSensorPoseOnVeh =
385 curObs->sensorPose + thisDepthSensorPoseWrtSensor;
387 const auto thisDepthSensorPose = vehiclePose + thisDepthSensorPoseOnVeh;
392 cam.setPose(thisDepthSensorPose);
394 auto tleRender = mrpt::system::CTimeLoggerEntry(
395 world_->getTimeLogger(),
"sensor.3Dlidar.renderSubScan");
397 fbo_renderer_depth_->render_depth(world3DScene, depthImage);
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;
407 if (rangeStdNoise_ > 0)
409 if (noiseSeq.empty())
411 noiseSeq.reserve(noiseLen);
412 for (
size_t i = 0; i < noiseLen; i++)
413 noiseSeq.push_back(rng.drawGaussian1D(0.0, rangeStdNoise_));
417 auto tleStore = mrpt::system::CTimeLoggerEntry(
418 world_->getTimeLogger(),
"sensor.3Dlidar.storeObs");
421 for (
int i = 0; i < numHorzRaysPerRender; i++)
423 const int iAbs = i + numHorzRaysPerRender * renderIdx;
424 if (iAbs >= rangeImage.cols())
427 for (
unsigned int j = 0; j < nRows; j++)
430 const auto& e = lut_.at(i).column.at(j);
434 ASSERTDEB_LT_(u, depthImage.cols());
435 ASSERTDEB_LT_(v, depthImage.rows());
438 float d = depthImage(v, u);
441 #if MRPT_VERSION >= 0x270 446 d = depth_log2lin_lut
447 [(d + 1.0f) * (depth_log2lin_t::NUM_ENTRIES - 1) / 2];
454 const float dNoisy = d + noiseSeq[noiseIdx++];
455 if (noiseIdx >= noiseLen) noiseIdx = 0;
457 if (dNoisy < 0 || dNoisy > maxRange_)
continue;
463 const float range = d * e.depth2range;
465 if (range <= 0 || range >= maxRange_)
continue;
467 ASSERTDEB_LT_(j, rangeImage.rows());
468 ASSERTDEB_LT_(iAbs, rangeImage.cols());
470 rangeImage(j, iAbs) = range;
473 const mrpt::math::TPoint3D pt_wrt_cam = {
474 d * (u - camModel.cx()) / camModel.fx(),
475 d * (v - camModel.cy()) / camModel.fy(), d};
477 thisDepthSensorPoseWrtSensor.composePoint(pt_wrt_cam));
483 if (ignore_parent_body_)
485 if (visVeh) visVeh->customVisualVisible(formerVisVehState);
486 if (veh) veh->chassisAndWheelsVisible(formerVisVehState);
489 #if MRPT_VERSION >= 0x270 490 viewport->enableShadowCasting(wasShadowEnabled);
495 auto tle3 = mrpt::system::CTimeLoggerEntry(
496 world_->getTimeLogger(),
"sensor.3Dlidar.acqObsMtx");
498 std::lock_guard<std::mutex> csl(last_scan_cs_);
499 last_scan_ = std::move(curObs);
500 last_scan2gui_ = last_scan_;
504 auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
506 auto tlePub = mrpt::system::CTimeLoggerEntry(
507 world_->getTimeLogger(),
"sensor.3Dlidar.report");
513 if (glCustomVisual_) glCustomVisual_->setVisibility(
true);
515 gui_uptodate_ =
false;
517 has_to_render_.reset();
void simulateOn3DScene(mrpt::opengl::COpenGLScene &gl_scene) override
std::map< std::string, TParamEntry > TParameterDefinitions
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const TParameterDefinitions ¶ms, const std::map< std::string, std::string > &variableNamesValues={}, const char *functionNameContext="", mrpt::system::COutputLogger *logger=nullptr)
static void RegisterSensorFOVViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
bool should_simulate_sensor(const TSimulContext &context)
void freeOpenGLResources() override
static void RegisterSensorOriginViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
void reportNewObservation(const std::shared_ptr< mrpt::obs::CObservation > &obs, const TSimulContext &context)
virtual void simul_pre_timestep(const TSimulContext &context) override
virtual void simul_post_timestep(const TSimulContext &context)
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
A 3D LiDAR sensor, with 360 degrees horizontal fielf-of-view, and a configurable vertical FOV...
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)
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
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:
void customVisualVisible(const bool visible)