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> 22 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF) 23 #include <mvsim/mvsim-msgs/ObservationLidar2D.pb.h> 26 using namespace mvsim;
53 params[
"fov_degrees"] =
TParamEntry(
"%lf", &fov_deg);
87 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
88 [[maybe_unused]]
const mrpt::optional_ref<mrpt::opengl::COpenGLScene>&
90 [[maybe_unused]]
bool childrenOnly)
92 using namespace std::string_literals;
94 mrpt::opengl::CSetOfObjects::Ptr glVizSensors;
97 glVizSensors = std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
98 viz->get().getByName(
"group_sensors_viz"));
99 if (!glVizSensors)
return;
105 gl_scan_ = mrpt::opengl::CPlanarLaserScan::Create();
110 gl_scan_->setPointsColor(ptsCol.R, ptsCol.G, ptsCol.B, ptsCol.A);
115 planeCol.R, planeCol.G, planeCol.B, planeCol.A);
119 gl_scan_->setLocalRepresentativePoint({0, 0, 0.10f});
128 #if MRPT_VERSION >= 0x270 132 mrpt::opengl::stock_objects::CornerXYZSimple(0.15
f);
143 #if MRPT_VERSION >= 0x270 147 auto fovScan = mrpt::opengl::CPlanarLaserScan::Create();
148 fovScan->enablePoints(
false);
149 fovScan->enableSurface(
true);
152 const float f = 0.30f;
153 for (
size_t i = 0; i < s.getScanSize(); i++)
155 s.setScanRange(i, f);
156 s.setScanRangeValidity(i,
true);
183 const double z_incrs = 1e-3;
184 const double z_offset = 1e-3;
187 gl_scan_->setPose(mrpt::poses::CPose3D(
188 p.x(), p.y(), z_offset + z_incrs *
z_order_, p.phi(), 0.0, 0.0));
217 mrpt::system::LVL_WARN,
218 "Time for a new sample came without still simulating the " 219 "last one (!) for simul_time=%.03f s.",
236 using mrpt::maps::COccupancyGridMap2D;
237 using mrpt::obs::CObservation2DRangeScan;
245 std::list<CObservation2DRangeScan> lstScans;
259 for (
const auto& element : elements)
265 const COccupancyGridMap2D& occGrid = grid->
getOccGrid();
269 CObservation2DRangeScan& scan = lstScans.back();
272 occGrid.laserScanSimulator(
283 lstScans.push_back(CObservation2DRangeScan(
scan_model_));
284 CObservation2DRangeScan& scan = lstScans.back();
287 std::map<b2Fixture*, uintptr_t> orgUserData;
289 auto makeFixtureInvisible = [&](
b2Fixture*
f) {
291 orgUserData[
f] =
f->GetUserData().pointer;
294 auto undoInvisibleFixtures = [&]() {
295 for (
auto& kv : orgUserData)
296 kv.first->GetUserData().pointer = kv.second;
299 if (
auto v = dynamic_cast<VehicleBase*>(&
vehicle_); v)
301 makeFixtureInvisible(v->get_fixture_chassis());
302 for (
auto&
f : v->get_fixture_wheels()) makeFixtureInvisible(
f);
315 float fraction)
override 344 const mrpt::poses::CPose2D sensorPose =
345 vehPose + mrpt::poses::CPose2D(scan.sensorPose);
346 const b2Vec2 sensorPt =
b2Vec2(sensorPose.x(), sensorPose.y());
353 scan.resizeScanAndAssign(nRays, maxRange,
false);
355 sensorPose.phi() + (scan.rightToLeft ? -0.5 : +0.5) * scan.aperture;
357 (scan.rightToLeft ? 1.0 : -1.0) * (scan.aperture / (nRays - 1));
360 thread_local mrpt::random::CRandomGenerator rnd;
362 for (
size_t i = 0; i < nRays; i++, A += AA)
365 sensorPt.
x +
cos(A) * maxRange, sensorPt.
y +
sin(A) * maxRange);
367 callback.hit_ =
false;
369 scan.setScanRangeValidity(i, callback.hit_);
376 mrpt::square(callback.point_.x - sensorPt.
x) +
377 mrpt::square(callback.point_.y - sensorPt.
y));
385 scan.setScanRange(i, range);
388 undoInvisibleFixtures();
396 auto lastScan = CObservation2DRangeScan::Create(
scan_model_);
399 lastScan->sensorLabel =
name_;
401 lastScan->resizeScanAndAssign(nRays, maxRange,
false);
403 for (
const auto& scan : lstScans)
405 for (
size_t i = 0; i < nRays; i++)
407 if (scan.getScanRangeValidity(i))
409 lastScan->setScanRange(
411 std::min(lastScan->getScanRange(i), scan.getScanRange(i)));
412 lastScan->setScanRangeValidity(i,
true);
441 using namespace mrpt;
448 auto tleWhole = mrpt::system::CTimeLoggerEntry(
451 auto tle1 = mrpt::system::CTimeLoggerEntry(
459 auto curObs = mrpt::obs::CObservation2DRangeScan::Create(
scan_model_);
465 curObs->sensorLabel =
name_;
467 curObs->resizeScanAndAssign(nRays, maxRange,
false);
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));
479 camModel.fy(camModel.fx());
483 mrpt::opengl::CFBORender::Parameters p;
485 p.height = FBO_NROWS;
491 auto viewport = world3DScene.getViewport();
495 const auto fixedAxisConventionRot =
496 mrpt::poses::CPose3D(0, 0, 0, -90.0_deg, 0.0_deg, -90.0_deg);
504 const auto firstAngle = curObs->getScanAngle(0);
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);
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)));
514 ASSERT_(numRaysPerRender > 0);
526 for (
int i = 0; i < numRaysPerRender; i++)
528 const auto ang = (scanIsCW ? -1 : 1) *
529 (camModel_FOV * 0.5 -
530 i * camModel_FOV / (numRaysPerRender - 1));
532 const auto pixelIdx = mrpt::saturate_val<int>(
533 mrpt::round(camModel.cx() - camModel.fx() * std::tan(ang)), 0,
550 cam.set6DOFMode(
true);
551 cam.setProjectiveFromPinhole(camModel);
554 #if MRPT_VERSION >= 0x270 555 const bool wasShadowEnabled = viewport->isShadowCastingEnabled();
556 viewport->enableShadowCasting(
false);
559 viewport->setViewportClipDistances(0.01, curObs->maxRange);
560 mrpt::math::CMatrixFloat depthImage;
565 bool formerVisVehState =
true;
571 visVeh->customVisualVisible(
false);
573 if (veh) veh->chassisAndWheelsVisible(
false);
576 for (
size_t renderIdx = 0; renderIdx < numRenders; renderIdx++)
578 const double thisRenderMidAngle =
579 firstAngle + (camModel_FOV / 2.0 + camModel_FOV * renderIdx) *
582 const auto depthSensorPose = vehiclePose + curObs->sensorPose +
583 mrpt::poses::CPose3D::FromYawPitchRoll(
584 thisRenderMidAngle, 0.0, 0.0) +
585 fixedAxisConventionRot;
590 cam.setPose(depthSensorPose);
592 auto tleRender = mrpt::system::CTimeLoggerEntry(
602 auto tleStore = mrpt::system::CTimeLoggerEntry(
606 thread_local mrpt::random::CRandomGenerator rng;
608 float*
d = depthImage.data();
609 const size_t N = depthImage.size();
610 for (
size_t i = 0; i < N; i++)
612 if (d[i] == 0)
continue;
617 if (dNoisy < 0 || dNoisy > curObs->maxRange)
continue;
623 auto tleStore = mrpt::system::CTimeLoggerEntry(
627 for (
int i = 0; i < numRaysPerRender; i++)
629 const auto scanRayIdx = numRaysPerRender * renderIdx + i;
631 if (scanRayIdx >= curObs->getScanSize())
break;
635 const float d = depthImage(0, u);
638 if (range <= 0 || range >= curObs->maxRange)
continue;
640 curObs->setScanRange(scanRayIdx, range);
641 curObs->setScanRangeValidity(scanRayIdx,
true);
648 if (visVeh) visVeh->customVisualVisible(formerVisVehState);
649 if (veh) veh->chassisAndWheelsVisible(formerVisVehState);
652 #if MRPT_VERSION >= 0x270 653 viewport->enableShadowCasting(wasShadowEnabled);
658 auto tle3 = mrpt::system::CTimeLoggerEntry(
669 auto tlePub = mrpt::system::CTimeLoggerEntry(
690 using namespace std::string_literals;
694 #if defined(MVSIM_HAS_ZMQ) && defined(MVSIM_HAS_PROTOBUF)
bool sensor_has_to_create_egl_context()
std::string publishTopic_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
constexpr uintptr_t INVISIBLE_FIXTURE_USER_DATA
Used to signal a Box2D fixture as "invisible" to sensors.
std::vector< size_t > angleIdx2pixelIdx_
std::map< std::string, TParamEntry > TParameterDefinitions
const WorldElementList & getListOfWorldElements() const
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)
mrpt::math::TPose3D getPose() const
mrpt::img::TColor viz_planeColor_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_
static void RegisterSensorFOVViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
mrpt::obs::CObservation2DRangeScan::Ptr last_scan_
std::mutex has_to_render_mtx_
std::unique_ptr< b2World > & getBox2DWorld()
bool should_simulate_sensor(const TSimulContext &context)
std::map< std::string, std::string > varValues_
Filled in by SensorBase::loadConfigFrom()
b2FixtureUserData & GetUserData()
const mrpt::maps::COccupancyGridMap2D & getOccGrid() const
mrpt::Clock::time_point get_simul_timestamp() const
mrpt::obs::CObservation2DRangeScan::Ptr last_scan2gui_
mrpt::obs::CObservation2DRangeScan scan_model_
static void RegisterSensorOriginViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
void freeOpenGLResources() override
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCustomVisual_
Simulable & vehicle_
The vehicle this sensor is attached to.
void registerOnServer(mvsim::Client &c) override
int z_order_
to help rendering multiple scans
void internal_simulate_lidar_2d_mode(const TSimulContext &context)
mrpt::poses::CPose2D getCPose2D() const
Alternative to getPose()
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)
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_depth_
virtual void simul_pre_timestep(const TSimulContext &context) override
uintptr_t pointer
For legacy compatibility.
virtual void simul_post_timestep(const TSimulContext &context)
const std::string & getName() const
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)
mrpt::system::CTimeLogger & getTimeLogger()
void advertiseTopic(const std::string &topicName)
mrpt::opengl::CPlanarLaserScan::Ptr gl_scan_
mrpt::img::TColor viz_pointsColor_
static int min(int n1, int n2)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
std::list< WorldElementBase::Ptr > WorldElementList
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
void mark_as_pending_running_sensors_on_3D_scene()
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)
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_
std::vector< float > angleIdx2secant_
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)
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_