CameraSensor.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2024 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/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>
17 #include <mvsim/VehicleBase.h>
18 #include <mvsim/World.h>
19 
20 #include "xml_utils.h"
21 
22 using namespace mvsim;
23 using namespace rapidxml;
24 
26  : SensorBase(parent)
27 {
28  this->loadConfigFrom(root);
29 }
30 
32 
34 {
35  gui_uptodate_ = false;
36 
39 
40  fbo_renderer_rgb_.reset();
41 
42  using namespace mrpt; // _deg
43  sensor_params_.cameraPose = mrpt::poses::CPose3D(0, 0, 0.5, 90.0_deg, 0, 90.0_deg);
44 
45  // Default values:
46  {
47  auto& c = sensor_params_.cameraParams;
48  c.ncols = 640;
49  c.nrows = 480;
50  c.cx(c.ncols / 2);
51  c.cy(c.nrows / 2);
52  c.fx(500);
53  c.fy(500);
54  }
55 
56  // Other scalar params:
57  TParameterDefinitions params;
58  params["pose_3d"] = TParamEntry("%pose3d", &sensor_params_.cameraPose);
59 
60  auto& rgbCam = sensor_params_.cameraParams;
61  params["cx"] = TParamEntry("%lf", &rgbCam.intrinsicParams(0, 2));
62  params["cy"] = TParamEntry("%lf", &rgbCam.intrinsicParams(1, 2));
63  params["fx"] = TParamEntry("%lf", &rgbCam.intrinsicParams(0, 0));
64  params["fy"] = TParamEntry("%lf", &rgbCam.intrinsicParams(1, 1));
65 
66  unsigned int rgb_ncols = rgbCam.ncols, rgb_nrows = rgbCam.nrows;
67  params["ncols"] = TParamEntry("%u", &rgb_ncols);
68  params["nrows"] = TParamEntry("%u", &rgb_nrows);
69 
70  params["clip_min"] = TParamEntry("%f", &rgbClipMin_);
71  params["clip_max"] = TParamEntry("%f", &rgbClipMax_);
72 
73  // Parse XML params:
75 
76  rgbCam.ncols = rgb_ncols;
77  rgbCam.nrows = rgb_nrows;
78 
79  // save sensor label here too:
80  sensor_params_.sensorLabel = name_;
81 }
82 
84  const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
85  [[maybe_unused]] const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& physical,
86  [[maybe_unused]] bool childrenOnly)
87 {
88  if (!gl_sensor_origin_ && viz)
89  {
90  gl_sensor_origin_ = mrpt::opengl::CSetOfObjects::Create();
91 #if MRPT_VERSION >= 0x270
92  gl_sensor_origin_->castShadows(false);
93 #endif
94  gl_sensor_origin_corner_ = mrpt::opengl::stock_objects::CornerXYZSimple(0.15f);
95 
97 
98  gl_sensor_origin_->setVisibility(false);
99  viz->get().insert(gl_sensor_origin_);
101  }
102  if (!gl_sensor_fov_ && viz)
103  {
104  gl_sensor_fov_ = mrpt::opengl::CSetOfObjects::Create();
105  gl_sensor_fov_->setVisibility(false);
106  viz->get().insert(gl_sensor_fov_);
108  }
109 
110  if (!gui_uptodate_)
111  {
112  {
113  std::lock_guard<std::mutex> csl(last_obs_cs_);
114  if (last_obs2gui_)
115  {
116  gl_sensor_origin_corner_->setPose(last_obs2gui_->sensorPose());
117 
118  if (!gl_sensor_frustum_)
119  {
120  gl_sensor_frustum_ = mrpt::opengl::CSetOfObjects::Create();
121 
122  const float frustumScale = 0.4e-3;
123  auto frustum =
124  mrpt::opengl::CFrustum::Create(last_obs2gui_->cameraParams, frustumScale);
125 
126  gl_sensor_frustum_->insert(frustum);
128  }
129 
130  using namespace mrpt; // _deg
131 
132  gl_sensor_frustum_->setPose(
133  last_obs2gui_->cameraPose +
134  (-mrpt::poses::CPose3D::FromYawPitchRoll(-90.0_deg, 0.0_deg, -90.0_deg)));
135 
136  last_obs2gui_.reset();
137  }
138  }
139  gui_uptodate_ = true;
140  }
141 
142  // Move with vehicle:
143  const auto& p = vehicle_.getPose();
144  const auto pp = parent()->applyWorldRenderOffset(p);
145 
146  gl_sensor_fov_->setPose(pp);
147  gl_sensor_origin_->setPose(pp);
148 
149  const auto globalSensorPose = pp + sensor_params_.cameraPose.asTPose();
150  if (glCustomVisual_) glCustomVisual_->setPose(globalSensorPose);
151 }
152 
153 void CameraSensor::simul_pre_timestep([[maybe_unused]] const TSimulContext& context) {}
154 
155 void CameraSensor::simulateOn3DScene(mrpt::opengl::COpenGLScene& world3DScene)
156 {
157  using namespace mrpt; // _deg
158 
159  {
160  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
161  if (!has_to_render_.has_value()) return;
162  }
163 
164  auto tleWhole = mrpt::system::CTimeLoggerEntry(world_->getTimeLogger(), "sensor.RGB");
165 
166  if (glCustomVisual_) glCustomVisual_->setVisibility(false);
167 
168  // Start making a copy of the pattern observation:
169  auto curObs = mrpt::obs::CObservationImage::Create(sensor_params_);
170 
171  // Set timestamp:
172  curObs->timestamp = world_->get_simul_timestamp();
173 
174  // Create FBO on first use, now that we are here at the GUI / OpenGL thread.
175  if (!fbo_renderer_rgb_)
176  {
177  mrpt::opengl::CFBORender::Parameters p;
178  p.width = sensor_params_.cameraParams.ncols;
179  p.height = sensor_params_.cameraParams.nrows;
180  p.create_EGL_context = world()->sensor_has_to_create_egl_context();
181 
182  fbo_renderer_rgb_ = std::make_shared<mrpt::opengl::CFBORender>(p);
183  }
184 
185  auto viewport = world3DScene.getViewport();
186 
187  auto& cam = fbo_renderer_rgb_->getCamera(world3DScene);
188 
189  const auto fixedAxisConventionRot =
190  mrpt::poses::CPose3D(0, 0, 0, -90.0_deg, 0.0_deg, -90.0_deg);
191 
192  // ----------------------------------------------------------
193  // RGB with its camera intrinsics & clip distances
194  // ----------------------------------------------------------
195  cam.set6DOFMode(true);
196  cam.setProjectiveFromPinhole(curObs->cameraParams);
197 
198  // RGB camera pose:
199  // vehicle (+) relativePoseOnVehicle (+) relativePoseIntensityWRTDepth
200  //
201  // Note: relativePoseOnVehicle should be (y,p,r)=(-90deg,0,-90deg) to make
202  // the camera to look forward:
203 
204  const auto vehiclePose = mrpt::poses::CPose3D(vehicle_.getPose());
205  const auto rgbSensorPose = vehiclePose + curObs->cameraPose;
206 
207  cam.setPose(world()->applyWorldRenderOffset(rgbSensorPose));
208 
209  ASSERT_(fbo_renderer_rgb_);
210 
211  auto tle2 = mrpt::system::CTimeLoggerEntry(world_->getTimeLogger(), "sensor.RGB.render");
212 
213  // viewport->setCustomBackgroundColor({0.3f, 0.3f, 0.3f, 1.0f});
214  viewport->setViewportClipDistances(rgbClipMin_, rgbClipMax_);
215 
216  fbo_renderer_rgb_->render_RGB(world3DScene, curObs->image);
217 
218  tle2.stop();
219 
220  // Store generated obs:
221  {
222  std::lock_guard<std::mutex> csl(last_obs_cs_);
223  last_obs_ = std::move(curObs);
225  }
226 
227  {
228  auto lckHasTo = mrpt::lockHelper(has_to_render_mtx_);
230 
231  if (glCustomVisual_) glCustomVisual_->setVisibility(true);
232 
233  gui_uptodate_ = false;
234  has_to_render_.reset();
235  }
236 }
237 
238 // Simulate sensor AFTER timestep, with the updated vehicle dynamical state:
240 {
243  {
244  has_to_render_ = context;
246  }
247 
248  // Keep sensor global pose up-to-date:
249  const auto& p = vehicle_.getPose();
250  const auto globalSensorPose = p + sensor_params_.cameraPose.asTPose();
251  Simulable::setPose(globalSensorPose, false /*do not notify*/);
252 }
253 
254 void CameraSensor::notifySimulableSetPose(const mrpt::math::TPose3D& newPose)
255 {
256  // The editor has moved the sensor in global coordinates.
257  // Convert back to local:
258  const auto& p = vehicle_.getPose();
259  sensor_params_.cameraPose = mrpt::poses::CPose3D(newPose - p);
260 }
261 
mvsim::VisualObject::parent
World * parent()
Definition: VisualObject.h:51
mvsim
Definition: Client.h:21
mvsim::CameraSensor::has_to_render_
std::optional< TSimulContext > has_to_render_
Definition: CameraSensor.h:69
mvsim::CameraSensor::last_obs2gui_
mrpt::obs::CObservationImage::Ptr last_obs2gui_
Definition: CameraSensor.h:61
mvsim::CameraSensor::loadConfigFrom
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
Definition: CameraSensor.cpp:33
mvsim::CameraSensor::simulateOn3DScene
void simulateOn3DScene(mrpt::opengl::COpenGLScene &gl_scene) override
Definition: CameraSensor.cpp:155
mvsim::VisualObject::world_
World * world_
Definition: VisualObject.h:73
mvsim::SensorBase::make_sure_we_have_a_name
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:252
mvsim::SensorBase::varValues_
std::map< std::string, std::string > varValues_
Filled in by SensorBase::loadConfigFrom()
Definition: SensorBase.h:97
mvsim::SensorBase::reportNewObservation
void reportNewObservation(const std::shared_ptr< mrpt::obs::CObservation > &obs, const TSimulContext &context)
Definition: SensorBase.cpp:159
mvsim::TParamEntry
Definition: TParameterDefinitions.h:38
mvsim::parse_xmlnode_children_as_param
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:215
mvsim::CameraSensor::freeOpenGLResources
void freeOpenGLResources() override
Definition: CameraSensor.cpp:262
mvsim::CameraSensor::~CameraSensor
virtual ~CameraSensor()
Definition: CameraSensor.cpp:31
mvsim::World::applyWorldRenderOffset
mrpt::math::TPose3D applyWorldRenderOffset(mrpt::math::TPose3D p) const
Definition: World.h:631
World.h
mvsim::SensorBase::vehicle_
Simulable & vehicle_
The vehicle this sensor is attached to.
Definition: SensorBase.h:82
mvsim::SensorBase
Virtual base class for all sensors.
Definition: SensorBase.h:34
mvsim::CameraSensor::has_to_render_mtx_
std::mutex has_to_render_mtx_
Definition: CameraSensor.h:70
mrpt
Definition: basic_types.h:36
mvsim::CameraSensor::rgbClipMin_
float rgbClipMin_
Definition: CameraSensor.h:72
mvsim::CameraSensor::internalGuiUpdate
virtual void internalGuiUpdate(const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &viz, const mrpt::optional_ref< mrpt::opengl::COpenGLScene > &physical, bool childrenOnly) override
Definition: CameraSensor.cpp:83
mvsim::World::sensor_has_to_create_egl_context
bool sensor_has_to_create_egl_context()
Definition: World.cpp:191
xml_utils.h
f
f
mvsim::SensorBase::should_simulate_sensor
bool should_simulate_sensor(const TSimulContext &context)
Definition: SensorBase.cpp:262
VehicleBase.h
mvsim::CameraSensor::last_obs_cs_
std::mutex last_obs_cs_
Definition: CameraSensor.h:58
mvsim::SensorBase::world
World * world()
Definition: SensorBase.h:84
rapidxml
Definition: rapidxml.hpp:57
mvsim::TSimulContext
Definition: basic_types.h:58
mvsim::CameraSensor::gl_sensor_origin_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_
Definition: CameraSensor.h:74
mvsim::World::get_simul_timestamp
mrpt::Clock::time_point get_simul_timestamp() const
Definition: World.h:137
mvsim::CameraSensor::gl_sensor_fov_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_fov_
Definition: CameraSensor.h:75
mvsim::TParameterDefinitions
std::map< std::string, TParamEntry > TParameterDefinitions
Definition: TParameterDefinitions.h:64
mvsim::Simulable::simul_post_timestep
virtual void simul_post_timestep(const TSimulContext &context)
Definition: Simulable.cpp:64
mvsim::World::mark_as_pending_running_sensors_on_3D_scene
void mark_as_pending_running_sensors_on_3D_scene()
Definition: World.h:223
mvsim::CameraSensor::gui_uptodate_
bool gui_uptodate_
Definition: CameraSensor.h:67
mvsim::Simulable::name_
std::string name_
Definition: Simulable.h:145
mvsim::CameraSensor::simul_pre_timestep
virtual void simul_pre_timestep(const TSimulContext &context) override
Definition: CameraSensor.cpp:153
mvsim::Simulable::setPose
void setPose(const mrpt::math::TPose3D &p, bool notifyChange=true) const
Definition: Simulable.cpp:474
rapidxml::xml_node< char >
mvsim::Simulable
Definition: Simulable.h:39
mvsim::CameraSensor::gl_sensor_frustum_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_frustum_
Definition: CameraSensor.h:75
mvsim::CameraSensor::notifySimulableSetPose
void notifySimulableSetPose(const mrpt::math::TPose3D &newPose) override
Definition: CameraSensor.cpp:254
mvsim::CameraSensor::gl_sensor_origin_corner_
mrpt::opengl::CSetOfObjects::Ptr gl_sensor_origin_corner_
Definition: CameraSensor.h:74
mvsim::CameraSensor::rgbClipMax_
float rgbClipMax_
Definition: CameraSensor.h:72
CameraSensor.h
mvsim::SensorBase::loadConfigFrom
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
Definition: SensorBase.cpp:231
mvsim::Simulable::getPose
mrpt::math::TPose3D getPose() const
Definition: Simulable.cpp:490
mvsim::World::getTimeLogger
mrpt::system::CTimeLogger & getTimeLogger()
Definition: World.h:321
root
root
mvsim::VisualObject::glCustomVisual_
std::shared_ptr< mrpt::opengl::CSetOfObjects > glCustomVisual_
Definition: VisualObject.h:77
mvsim::CameraSensor::sensor_params_
mrpt::obs::CObservationImage sensor_params_
Definition: CameraSensor.h:56
mvsim::CameraSensor::simul_post_timestep
virtual void simul_post_timestep(const TSimulContext &context) override
Definition: CameraSensor.cpp:239
mvsim::CameraSensor::last_obs_
mrpt::obs::CObservationImage::Ptr last_obs_
Definition: CameraSensor.h:60
mvsim::SensorBase::RegisterSensorFOVViz
static void RegisterSensorFOVViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
Definition: SensorBase.cpp:73
mvsim::SensorBase::RegisterSensorOriginViz
static void RegisterSensorOriginViz(const std::shared_ptr< mrpt::opengl::CSetOfObjects > &o)
Definition: SensorBase.cpp:78
mvsim::CameraSensor::fbo_renderer_rgb_
std::shared_ptr< mrpt::opengl::CFBORender > fbo_renderer_rgb_
Definition: CameraSensor.h:63
mvsim::CameraSensor::CameraSensor
CameraSensor(Simulable &parent, const rapidxml::xml_node< char > *root)
Definition: CameraSensor.cpp:25


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:07