LaserScanner.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014 Jose Luis Blanco Claraco (University of Almeria) |
5  | Copyright (C) 2017 Borys Tymchenko (Odessa Polytechnic University) |
6  | Distributed under GNU General Public License version 3 |
7  | See <http://www.gnu.org/licenses/> |
8  +-------------------------------------------------------------------------+ */
9 
10 #include <mvsim/World.h>
13 #include <mvsim/VehicleBase.h>
14 #include <mrpt/opengl/COpenGLScene.h>
15 #include <mrpt/random.h>
16 #include <mrpt/version.h>
17 
18 #include "xml_utils.h"
19 
20 using namespace mvsim;
21 using namespace rapidxml;
22 
23 int z_order_cnt = 0;
24 
26  VehicleBase& parent, const rapidxml::xml_node<char>* root)
27  : SensorBase(parent),
28  m_z_order(++z_order_cnt),
29  m_rangeStdNoise(0.01),
30  m_angleStdNoise(DEG2RAD(0.01)),
31  m_see_fixtures(true)
32 {
33  this->loadConfigFrom(root);
34 }
35 
38 {
39  m_gui_uptodate = false;
40 
41  // Attribs:
42  std::map<std::string, TParamEntry> attribs;
43  attribs["name"] = TParamEntry("%s", &this->m_name);
44 
45  parse_xmlnode_attribs(*root, attribs, "[LaserScanner]");
46 
47  // Other scalar params:
48  int nRays = 181;
49  double fov_deg = 180;
50 
51  std::map<std::string, TParamEntry> params;
52  params["fov_degrees"] = TParamEntry("%lf", &fov_deg);
53  params["nrays"] = TParamEntry("%i", &nRays);
54  params["pose"] = TParamEntry("%pose2d_ptr3d", &m_scan_model.sensorPose);
55  params["range_std_noise"] = TParamEntry("%lf", &m_rangeStdNoise);
56  params["angle_std_noise_deg"] = TParamEntry("%lf_deg", &m_angleStdNoise);
57  params["sensor_period"] = TParamEntry("%lf", &this->m_sensor_period);
58  params["bodies_visible"] = TParamEntry("%bool", &this->m_see_fixtures);
59 
60  // Parse XML params:
61  parse_xmlnode_children_as_param(*root, params);
62 
63  // Pass params to the scan2D obj:
64  m_scan_model.aperture = DEG2RAD(fov_deg);
65 #if MRPT_VERSION >= 0x150
66  m_scan_model.resizeScan(nRays);
67 #else
68  m_scan_model.scan.resize(nRays);
69  m_scan_model.validRange.resize(nRays);
70 #endif
71 
72  // Assign a sensible default name/sensor label if none is provided:
73  if (m_name.empty())
74  {
75  const size_t nextIdx = m_vehicle.getSensors().size() + 1;
76  m_name = mrpt::format("laser%u", static_cast<unsigned int>(nextIdx));
77  }
78 }
79 
80 void LaserScanner::gui_update(mrpt::opengl::COpenGLScene& scene)
81 {
82  // 1st time?
83  if (!m_gl_scan)
84  {
85  m_gl_scan = mrpt::opengl::CPlanarLaserScan::Create();
86  m_gl_scan->setSurfaceColor(0.0f, 0.0f, 1.0f, 0.05f);
88  }
89 
90  if (!m_gui_uptodate)
91  {
92  {
93  std::lock_guard<std::mutex> csl(m_last_scan_cs);
94  if (m_last_scan2gui)
95  {
96  m_gl_scan->setScan(*m_last_scan2gui);
97  m_last_scan2gui.reset();
98  }
99  }
100  m_gui_uptodate = true;
101  }
102 
103  const double z_incrs = 10e-3; // for m_z_order
104  const double z_offset = 10e-2;
105  const mrpt::poses::CPose2D& p = m_vehicle.getCPose2D();
106  m_gl_scan->setPose(
107  mrpt::poses::CPose3D(
108  p.x(), p.y(), z_offset + z_incrs * m_z_order, p.phi(), 0.0, 0.0));
109 }
110 
112 // Simulate sensor AFTER timestep, with the updated vehicle dynamical state:
114 {
115  // Limit sensor rate:
116  if (context.simul_time < m_sensor_last_timestamp + m_sensor_period) return;
117 
119 
120  // Create an array of scans, each reflecting ranges to one kind of world
121  // objects.
122  // Finally, we'll take the shortest range in each direction:
123  std::list<CObservation2DRangeScan> lstScans;
124 
125  const size_t nRays = m_scan_model.scan.size();
126  const double maxRange = m_scan_model.maxRange;
127 
128  // Get pose of the robot:
129  const mrpt::poses::CPose2D& vehPose = m_vehicle.getCPose2D();
130 
131  // grid maps:
132  // -------------
133  m_world->getTimeLogger().enter("LaserScanner.scan.1.gridmap");
134 
135  const World::TListWorldElements& elements =
137  for (World::TListWorldElements::const_iterator it = elements.begin();
138  it != elements.end(); ++it)
139  {
140  // If not a grid map, ignore:
141  const OccupancyGridMap* grid =
142  dynamic_cast<const OccupancyGridMap*>(*it);
143  if (!grid) continue;
144  const COccupancyGridMap2D& occGrid = grid->getOccGrid();
145 
146  // Create new scan:
147  lstScans.push_back(CObservation2DRangeScan(m_scan_model));
148  CObservation2DRangeScan& scan = lstScans.back();
149 
150  // Ray tracing over the gridmap:
151  occGrid.laserScanSimulator(
152  scan, vehPose, 0.5f, m_scan_model.scan.size(), m_rangeStdNoise, 1,
154  }
155  m_world->getTimeLogger().leave("LaserScanner.scan.1.gridmap");
156 
157  // ray trace on Box2D polygons:
158  // ------------------------------
159  m_world->getTimeLogger().enter("LaserScanner.scan.2.polygons");
160  {
161  // Create new scan:
162  lstScans.push_back(CObservation2DRangeScan(m_scan_model));
163  CObservation2DRangeScan& scan = lstScans.back();
164 
165  // Do Box2D raycasting stuff:
166  // ------------------------------
167  // This callback finds the closest hit. Polygon 0 is filtered.
168  class RayCastClosestCallback : public b2RayCastCallback
169  {
170  public:
171  RayCastClosestCallback() : m_see_fixtures(true), m_hit(false) {}
172  float32 ReportFixture(
173  b2Fixture* fixture, const b2Vec2& point, const b2Vec2& normal,
174  float32 fraction)
175  {
176  if (!m_see_fixtures ||
178  {
179  // By returning -1, we instruct the calling code to ignore
180  // this fixture and
181  // continue the ray-cast to the next fixture.
182  return -1.0f;
183  }
184 
185  m_hit = true;
186  m_point = point;
187  m_normal = normal;
188  // By returning the current fraction, we instruct the calling
189  // code to clip the ray and
190  // continue the ray-cast to the next fixture. WARNING: do not
191  // assume that fixtures
192  // are reported in order. However, by clipping, we can always
193  // get the closest fixture.
194  return fraction;
195  }
196 
197  bool m_see_fixtures;
198  bool m_hit;
199  b2Vec2 m_point;
200  b2Vec2 m_normal;
201  };
202 
203  const mrpt::poses::CPose2D sensorPose =
204  vehPose + mrpt::poses::CPose2D(scan.sensorPose);
205  const b2Vec2 sensorPt = b2Vec2(sensorPose.x(), sensorPose.y());
206 
207  RayCastClosestCallback callback;
208  callback.m_see_fixtures = m_see_fixtures;
209 
210  // Scan size:
211  ASSERT_(nRays >= 2);
212 #if MRPT_VERSION >= 0x150
213  scan.resizeScan(nRays);
214 #else
215  scan.scan.resize(nRays);
216  scan.validRange.resize(nRays);
217 #endif
218  double A =
219  sensorPose.phi() + (scan.rightToLeft ? -0.5 : +0.5) * scan.aperture;
220  const double AA =
221  (scan.rightToLeft ? 1.0 : -1.0) * (scan.aperture / (nRays - 1));
222 
223  auto &rnd =
224 #if MRPT_VERSION >= 0x199
225  mrpt::random::getRandomGenerator();
226 #else
227  mrpt::random::randomGenerator;
228 #endif
229 
230  for (size_t i = 0; i < nRays; i++, A += AA)
231  {
232  const b2Vec2 endPt = b2Vec2(
233  sensorPt.x + cos(A) * maxRange, sensorPt.y + sin(A) * maxRange);
234 
235  callback.m_hit = false;
236  m_world->getBox2DWorld()->RayCast(&callback, sensorPt, endPt);
237 #if MRPT_VERSION >= 0x150
238  scan.setScanRangeValidity(i, callback.m_hit);
239 #else
240  scan.validRange[i] = callback.m_hit ? 1 : 0;
241 #endif
242 
243  float range = scan.scan[i];
244  if (callback.m_hit)
245  {
246  // Hit:
247  range = ::hypotf(
248  callback.m_point.x - sensorPt.x,
249  callback.m_point.y - sensorPt.y);
250  range +=
251  rnd.drawGaussian1D_normalized() *
253  }
254  else
255  {
256  // Miss:
257  range = maxRange;
258  }
259 #if MRPT_VERSION >= 0x150
260  scan.setScanRange(i, range);
261 #else
262  scan.scan[i] = range;
263 #endif
264  } // end for (raycast scan)
265  }
266  m_world->getTimeLogger().leave("LaserScanner.scan.2.polygons");
267 
268  // Summarize all scans in one single scan:
269  // ----------------------------------------
270  m_world->getTimeLogger().enter("LaserScanner.scan.3.merge");
271 
272  CObservation2DRangeScan* lastScan =
273  new CObservation2DRangeScan(m_scan_model);
274  lastScan->timestamp = mrpt::system::now();
275  lastScan->sensorLabel = m_name;
276 
277 #if MRPT_VERSION >= 0x150
278  lastScan->resizeScanAndAssign(nRays, maxRange, false);
279 #else
280  lastScan->scan.assign(nRays, maxRange);
281  lastScan->validRange.assign(nRays, 0);
282 #endif
283 
284  for (std::list<CObservation2DRangeScan>::const_iterator it =
285  lstScans.begin();
286  it != lstScans.end(); ++it)
287  {
288  ASSERT_(it->scan.size() == nRays && it->validRange.size() == nRays);
289 
290  for (size_t i = 0; i < nRays; i++)
291  {
292  if (it->validRange[i])
293  {
294 #if MRPT_VERSION >= 0x150
295  lastScan->setScanRange(
296  i, std::min(lastScan->scan[i], it->scan[i]));
297  lastScan->setScanRangeValidity(i, true);
298 #else
299  lastScan->scan[i] = std::min(lastScan->scan[i], it->scan[i]);
300  lastScan->validRange[i] = 1; // valid
301 #endif
302  }
303  }
304  }
305  m_world->getTimeLogger().leave("LaserScanner.scan.3.merge");
306 
307  {
308  std::lock_guard<std::mutex> csl(m_last_scan_cs);
309  m_last_scan = CObservation2DRangeScan::Ptr(lastScan);
311  }
312 
314 
315  m_gui_uptodate = false;
316 }
std::list< WorldElementBase * > TListWorldElements
getListOfVehicles()
Definition: World.h:170
f
double simul_time
Current time in the simulated world.
Definition: basic_types.h:56
LaserScanner(VehicleBase &parent, const rapidxml::xml_node< char > *root)
A 2D column vector.
Definition: b2Math.h:53
virtual void onNewObservation(const VehicleBase &veh, const mrpt::slam::CObservation *obs)
Definition: World.h:220
const TListSensors & getSensors() const
Definition: VehicleBase.h:131
virtual void simul_post_timestep(const TSimulContext &context)
See docs in base class.
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
See docs in base class.
void parse_xmlnode_attribs(const rapidxml::xml_node< char > &xml_node, const std::map< std::string, TParamEntry > &params, const char *function_name_context="")
Definition: xml_utils.cpp:160
std::string m_name
sensor label/name
Definition: LaserScanner.h:49
CTimeLogger & getTimeLogger()
Definition: World.h:190
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const std::map< std::string, TParamEntry > &params, const char *function_name_context="")
Definition: xml_utils.cpp:196
void RayCast(b2RayCastCallback *callback, const b2Vec2 &point1, const b2Vec2 &point2) const
Definition: b2World.cpp:1019
VehicleBase & m_vehicle
(in seconds) (Default = 0.1)
Definition: SensorBase.h:40
#define SCENE_INSERT_Z_ORDER(_SCENE, _ZORDER_INDEX, _OBJ_TO_INSERT)
Definition: VisualObject.h:37
mrpt::obs::CObservation2DRangeScan::Ptr m_last_scan
Last simulated scan.
Definition: LaserScanner.h:62
#define INVISIBLE_FIXTURE_USER_DATA
Used to signal a Box2D fixture as "invisible" to sensors.
Definition: basic_types.h:19
virtual void gui_update(mrpt::opengl::COpenGLScene &scene)
See docs in base class.
CObservation2DRangeScan m_scan_model
or not (Default=true)
Definition: LaserScanner.h:55
float32 y
Definition: b2Math.h:140
const COccupancyGridMap2D & getOccGrid() const
mrpt::obs::CObservation2DRangeScan::Ptr m_last_scan2gui
Definition: LaserScanner.h:63
int m_z_order
to help rendering multiple scans
Definition: LaserScanner.h:47
double m_sensor_period
Definition: SensorBase.h:36
b2World * getBox2DWorld()
Definition: World.h:178
virtual void simul_pre_timestep(const TSimulContext &context)
See docs in base class.
int z_order_cnt
mrpt::poses::CPose2D getCPose2D() const
const TListWorldElements & getListOfWorldElements() const
Definition: World.h:185
float32 x
Definition: b2Math.h:140
double m_sensor_last_timestamp
Definition: SensorBase.h:42
mrpt::opengl::CPlanarLaserScan::Ptr m_gl_scan
call of gui_update() from m_last_scan2gui
Definition: LaserScanner.h:67
std::mutex m_last_scan_cs
Definition: LaserScanner.h:60
float float32
Definition: b2Settings.h:35
void * GetUserData() const
Definition: b2Fixture.h:263


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 19:36:40