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> 22 using namespace mvsim;
46 mrpt::poses::CPose3D(0, 0, 0.5, 90.0_deg, 0, 90.0_deg);
63 params[
"relativePoseIntensityWRTDepth"] =
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));
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);
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));
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);
101 depthCam.ncols = depth_ncols;
102 depthCam.nrows = depth_nrows;
104 rgbCam.ncols = rgb_ncols;
105 rgbCam.nrows = rgb_nrows;
115 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
116 [[maybe_unused]]
const mrpt::optional_ref<mrpt::opengl::COpenGLScene>&
118 [[maybe_unused]]
bool childrenOnly)
120 mrpt::opengl::CSetOfObjects::Ptr glVizSensors;
123 glVizSensors = std::dynamic_pointer_cast<mrpt::opengl::CSetOfObjects>(
124 viz->get().getByName(
"group_sensors_viz"));
125 if (!glVizSensors)
return;
131 gl_obs_ = mrpt::opengl::CPointCloudColoured::Create();
133 gl_obs_->setLocalRepresentativePoint(
141 #if MRPT_VERSION >= 0x270 145 mrpt::opengl::stock_objects::CornerXYZSimple(0.15
f);
169 mrpt::obs::T3DPointsProjectionParams pp;
170 pp.takeIntoAccountSensorPoseOnRobot =
true;
181 const float frustumScale = 0.4e-3;
182 auto frustum = mrpt::opengl::CFrustum::Create(
214 mrpt::opengl::COpenGLScene& world3DScene)
216 using namespace mrpt;
226 auto tle1 = mrpt::system::CTimeLoggerEntry(
234 auto curObsPtr = mrpt::obs::CObservation3DRangeScan::Create(
sensor_params_);
235 auto& curObs = *curObsPtr;
243 auto tle2 = mrpt::system::CTimeLoggerEntry(
246 mrpt::opengl::CFBORender::Parameters p;
256 auto tle2 = mrpt::system::CTimeLoggerEntry(
259 mrpt::opengl::CFBORender::Parameters p;
267 auto viewport = world3DScene.getViewport();
276 const auto fixedAxisConventionRot =
277 mrpt::poses::CPose3D(0, 0, 0, -90.0_deg, 0.0_deg, -90.0_deg);
291 const auto depthSensorPose =
292 vehiclePose + curObs.sensorPose + fixedAxisConventionRot;
294 const auto rgbSensorPose =
295 vehiclePose + curObs.sensorPose + curObs.relativePoseIntensityWRTDepth;
299 auto tle2 = mrpt::system::CTimeLoggerEntry(
302 camRGB->set6DOFMode(
true);
303 camRGB->setProjectiveFromPinhole(curObs.cameraParamsIntensity);
304 camRGB->setPose(rgbSensorPose);
311 curObs.hasIntensityImage =
true;
315 curObs.hasIntensityImage =
false;
323 auto tle2 = mrpt::system::CTimeLoggerEntry(
326 camDepth->setProjectiveFromPinhole(curObs.cameraParams);
331 camDepth->set6DOFMode(
true);
332 camDepth->setPose(depthSensorPose);
337 auto tle2c = mrpt::system::CTimeLoggerEntry(
345 curObs.hasRangeImage =
true;
346 curObs.range_is_depth =
true;
348 auto tle2cnv = mrpt::system::CTimeLoggerEntry(
353 curObs.rangeImage = (
depthImage_.asEigen().cwiseMin(curObs.maxRange) /
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;
367 if (noiseSeq.empty())
369 noiseSeq.reserve(noiseLen);
370 for (
size_t i = 0; i < noiseLen; i++)
372 noiseSeq.push_back(static_cast<int16_t>(mrpt::round(
374 curObs.rangeUnits)));
378 auto tle2noise = mrpt::system::CTimeLoggerEntry(
381 uint16_t*
d = curObs.rangeImage.data();
382 const size_t N = curObs.rangeImage.size();
384 const int16_t maxRangeInts =
385 static_cast<int16_t
>(curObs.maxRange / curObs.rangeUnits);
387 for (
size_t i = 0; i < N; i++)
389 if (d[i] == 0)
continue;
391 const int16_t dNoisy =
392 static_cast<int16_t
>(d[i]) + noiseSeq[noiseIdx++];
394 if (noiseIdx >= noiseLen) noiseIdx = 0;
396 if (dNoisy > maxRangeInts)
continue;
398 d[i] =
static_cast<uint16_t
>(dNoisy);
404 curObs.hasRangeImage =
false;
409 auto tle3 = mrpt::system::CTimeLoggerEntry(
420 auto tlePub = mrpt::system::CTimeLoggerEntry(
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_rgb_
bool sensor_has_to_create_egl_context()
mrpt::opengl::CPointCloudColoured::Ptr gl_obs_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
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)
mrpt::math::TPose3D getPose() const
bool sense_depth_
Simulate the DEPTH sensor part.
mrpt::math::CMatrixFloat depthImage_
static void RegisterSensorFOVViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
bool should_simulate_sensor(const TSimulContext &context)
std::map< std::string, std::string > varValues_
Filled in by SensorBase::loadConfigFrom()
DepthCameraSensor(Simulable &parent, const rapidxml::xml_node< char > *root)
mrpt::Clock::time_point get_simul_timestamp() const
static void RegisterSensorOriginViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCustomVisual_
Simulable & vehicle_
The vehicle this sensor is attached to.
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)
mrpt::obs::CObservation3DRangeScan sensor_params_
std::mutex has_to_render_mtx_
std::optional< TSimulContext > has_to_render_
virtual void simul_post_timestep(const TSimulContext &context)
bool sense_rgb_
Simulate the RGB sensor part.
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
mrpt::system::CTimeLogger & getTimeLogger()
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()
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:
mrpt::obs::CObservation3DRangeScan::Ptr last_obs_
virtual ~DepthCameraSensor()
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