OccupancyGridMap.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 
11 #include <mvsim/World.h>
12 #include "xml_utils.h"
13 
14 #include <mrpt/opengl/COpenGLScene.h>
15 #include <mrpt/poses/CPose2D.h>
16 #include <mrpt/utils/CFileGZInputStream.h>
17 #include <mrpt/system/filesystem.h>
18 #include <rapidxml.hpp>
19 
20 #include <mrpt/version.h>
21 #if MRPT_VERSION >= 0x130
22 #include <mrpt/maps/CSimplePointsMap.h>
23 using mrpt::maps::CSimplePointsMap;
24 #else
25 #include <mrpt/slam/CSimplePointsMap.h>
26 using mrpt::slam::CSimplePointsMap;
27 #endif
28 
29 #if MRPT_VERSION >= 0x199
30 #include <mrpt/serialization/CArchive.h>
31 #endif
32 
33 
34 using namespace rapidxml;
35 using namespace mvsim;
36 using namespace std;
37 
38 OccupancyGridMap::OccupancyGridMap(
39  World* parent, const rapidxml::xml_node<char>* root)
40  : WorldElementBase(parent),
41  m_gui_uptodate(false),
42  m_show_grid_collision_points(true),
43  m_restitution(0.01),
44  m_lateral_friction(0.5)
45 {
46  loadConfigFrom(root);
47 }
48 
51 {
52  m_gui_uptodate = false;
53 
54  // <file>FILENAME.{png,gridmap}</file>
55  xml_node<>* xml_file = root->first_node("file");
56  if (!xml_file || !xml_file->value())
57  throw std::runtime_error(
58  "Error: <file></file> XML entry not found inside gridmap node!");
59 
60  const string sFile = m_world->resolvePath(xml_file->value());
61  const string sFileExt =
62  mrpt::system::extractFileExtension(sFile, true /*ignore gz*/);
63 
64  // MRPT gridmaps format:
65  if (sFileExt == "gridmap")
66  {
67  mrpt::utils::CFileGZInputStream fi(sFile);
68 #if MRPT_VERSION>=0x199
69  auto f = mrpt::serialization::archiveFrom(fi);
70 #else
71  auto &f = fi;
72 #endif
73  f >> m_grid;
74  }
75  else
76  // Assume it's an image:
77  {
78  std::map<std::string, TParamEntry> other_params;
79  double xcenterpixel = -1, ycenterpixel = -1;
80  double resolution = 0.10;
81 
82  other_params["resolution"] = TParamEntry("%lf", &resolution);
83  other_params["centerpixel_x"] = TParamEntry("%lf", &xcenterpixel);
84  other_params["centerpixel_y"] = TParamEntry("%lf", &ycenterpixel);
85 
86  parse_xmlnode_children_as_param(*root, other_params);
87 
88  if (!m_grid.loadFromBitmapFile(
89  sFile, resolution,
90 #if MRPT_VERSION>=0x199
91  {xcenterpixel, ycenterpixel}
92 #else
93  xcenterpixel, ycenterpixel
94 #endif
95  ))
96  throw std::runtime_error(
97  mrpt::format(
98  "[OccupancyGridMap] ERROR: File not found '%s'",
99  sFile.c_str()));
100  }
101 
102  {
103  // Other general params:
104  std::map<std::string, TParamEntry> ps;
105  ps["show_collisions"] =
107  ps["restitution"] = TParamEntry("%lf", &m_restitution);
108  ps["lateral_friction"] = TParamEntry("%lf", &m_lateral_friction);
109 
111  }
112 }
113 
114 void OccupancyGridMap::gui_update(mrpt::opengl::COpenGLScene& scene)
115 {
116  using namespace mrpt::math;
117 
118  // 1st time call?? -> Create objects
119  if (!m_gl_grid)
120  {
121  m_gl_grid = mrpt::opengl::CSetOfObjects::Create();
122  SCENE_INSERT_Z_ORDER(scene, 0, m_gl_grid);
123  }
124  if (m_gl_obs_clouds.size() != m_obstacles_for_each_obj.size())
125  {
127  }
128 
129  // 1st call OR gridmap changed?
130  if (!m_gui_uptodate)
131  {
132  m_grid.getAs3DObject(m_gl_grid);
133  m_gui_uptodate = true;
134  }
135 
136  // Update obstacles:
137  {
138  std::lock_guard<std::mutex> csl(m_gl_obs_clouds_buffer_cs);
139  for (size_t i = 0; i < m_gl_obs_clouds.size(); i++)
140  {
141  mrpt::opengl::CSetOfObjects::Ptr& gl_objs = m_gl_obs_clouds[i];
142  if (!gl_objs)
143  {
144  gl_objs = mrpt::opengl::CSetOfObjects::Create();
145  MRPT_TODO("Add a name, and remove old ones in scene, etc.")
146  SCENE_INSERT_Z_ORDER(scene, 1, gl_objs);
147  }
148 
149  // Now that we are in a safe thread (with the OpenGL scene lock
150  // adquired from the caller)
151  // proceed to replace the old with the new point cloud:
152  gl_objs->clear();
153  if (m_gl_obs_clouds_buffer.size() > i)
154  gl_objs->insert(m_gl_obs_clouds_buffer[i]);
155  }
156 
157  m_gl_obs_clouds_buffer.clear();
158  } // end lock
159 }
160 
162 {
163  // Make a list of objects subject to collide with the occupancy grid:
164  // - Vehicles
165  // - Blocks
166  {
167  const World::TListVehicles& lstVehs =
168  this->m_world->getListOfVehicles();
169  const World::TListBlocks& lstBlocks = this->m_world->getListOfBlocks();
170  const size_t nObjs = lstVehs.size() + lstBlocks.size();
171 
172  m_obstacles_for_each_obj.resize(nObjs);
173  size_t obj_idx = 0;
174  for (World::TListVehicles::const_iterator itVeh = lstVehs.begin();
175  itVeh != lstVehs.end(); ++itVeh, ++obj_idx)
176  {
179  itVeh->second->getMaxVehicleRadius() * 1.50f;
180  const mrpt::math::TPose3D& pose = itVeh->second->getPose();
181  ipv.pose = mrpt::poses::CPose2D(
182  pose.x, pose.y,
183  0 /* angle=0, no need to rotate everything to later rotate back again! */);
184  }
185  for (World::TListBlocks::const_iterator it = lstBlocks.begin();
186  it != lstBlocks.end(); ++it, ++obj_idx)
187  {
189  ipv.max_obstacles_ranges = it->second->getMaxBlockRadius() * 1.50f;
190  const mrpt::math::TPose3D& pose = it->second->getPose();
191  ipv.pose = mrpt::poses::CPose2D(
192  pose.x, pose.y,
193  0 /* angle=0, no need to rotate everything to later rotate back again! */);
194  }
195  }
196 
197  // For each object, create a ground body with fixtures at each scanned point
198  // around the vehicle, so it can collide with the environment:
199  // Upon first usage, reserve mem:
200  { // lock
201  std::lock_guard<std::mutex> csl(m_gl_obs_clouds_buffer_cs);
202  const size_t nObjs = m_obstacles_for_each_obj.size();
203  m_gl_obs_clouds_buffer.resize(nObjs);
204 
205  for (size_t obj_idx = 0; obj_idx < nObjs; obj_idx++)
206  {
207  // 1) Simulate scan to get obstacles around the vehicle:
209  CObservation2DRangeScan::Ptr& scan = ipv.scan;
210  // Upon first time, reserve mem:
211  if (!scan)
212  scan = CObservation2DRangeScan::Create();
213 
214  const float veh_max_obstacles_ranges = ipv.max_obstacles_ranges;
215  const float occup_threshold = 0.5f;
216  const size_t nRays = 50;
217 
218  scan->aperture = 2.0 * M_PI; // 360 field of view
219  scan->maxRange = veh_max_obstacles_ranges;
220 
221  m_grid.laserScanSimulator(
222  *scan, ipv.pose, occup_threshold, nRays, 0.0f /*noise*/);
223 
224  // Since we'll dilate obstacle points, let's give a bit more space
225  // as compensation:
226  const float range_enlarge = 0.25f * m_grid.getResolution();
227  for (size_t k = 0; k < scan->scan.size(); k++)
228  {
229 #if MRPT_VERSION >= 0x150
230  scan->setScanRange(k, scan->getScanRange(k) + range_enlarge);
231 #else
232  scan->scan[k] += range_enlarge;
233 #endif
234  }
235  // 2) Create a Box2D "ground body" with square "fixtures" so the
236  // vehicle can collide with the occ. grid:
237  b2World* b2world = m_world->getBox2DWorld();
238 
239  // Create Box2D objects upon first usage:
240  if (!ipv.collide_body)
241  {
242  b2BodyDef bdef;
243  ipv.collide_body = b2world->CreateBody(&bdef);
244  ASSERT_(ipv.collide_body);
245  }
246  // Force move the body to the vehicle origins (to use obstacles in
247  // local coords):
249  b2Vec2(ipv.pose.x(), ipv.pose.y()), .0f);
250 
251  // GL:
252  // 1st usage?
253  mrpt::opengl::CPointCloud::Ptr& gl_pts =
254  m_gl_obs_clouds_buffer[obj_idx];
256  {
257  gl_pts = mrpt::opengl::CPointCloud::Create();
258  gl_pts->setPointSize(4.0f);
259  gl_pts->setColor(0, 0, 1);
260 
261  gl_pts->setVisibility(m_show_grid_collision_points);
262  gl_pts->setPose(mrpt::poses::CPose2D(ipv.pose));
263  gl_pts->clear();
264  }
265 
266  // Physical properties of each "occupied cell":
267  const float occCellSemiWidth = m_grid.getResolution() * 0.4f;
268  b2PolygonShape sqrPoly;
269  sqrPoly.SetAsBox(occCellSemiWidth, occCellSemiWidth);
270  sqrPoly.m_radius = 1e-3; // The "skin" depth of the body
271  b2FixtureDef fixtureDef;
272  fixtureDef.shape = &sqrPoly;
273  fixtureDef.restitution = m_restitution;
274  fixtureDef.density = 0; // Fixed (inf. mass)
275  fixtureDef.friction = m_lateral_friction; // 0.5f;
276 
277  // Create fixtures at their place (or disable it if no obstacle has
278  // been sensed):
279  const CSinCosLookUpTableFor2DScans::TSinCosValues& sincos_tab =
280  m_sincos_lut.getSinCosForScan(*scan);
281  ipv.collide_fixtures.resize(nRays);
282  for (size_t k = 0; k < nRays; k++)
283  {
284  if (!ipv.collide_fixtures[k].fixture)
285  ipv.collide_fixtures[k].fixture =
286  ipv.collide_body->CreateFixture(&fixtureDef);
287 
288  if (!scan->validRange[k])
289  {
290  ipv.collide_fixtures[k].fixture->SetSensor(
291  true); // Box2D's way of saying: don't collide with
292  // this!
293  ipv.collide_fixtures[k].fixture->SetUserData(
295  }
296  else
297  {
298  ipv.collide_fixtures[k].fixture->SetSensor(
299  false); // Box2D's way of saying: don't collide with
300  // this!
301  ipv.collide_fixtures[k].fixture->SetUserData(NULL);
302 
303  b2PolygonShape* poly = dynamic_cast<b2PolygonShape*>(
304  ipv.collide_fixtures[k].fixture->GetShape());
305  ASSERT_(poly != NULL);
306 
307  const float llx = sincos_tab.ccos[k] * scan->scan[k];
308  const float lly = sincos_tab.csin[k] * scan->scan[k];
309 
310  const float ggx = ipv.pose.x() + llx;
311  const float ggy = ipv.pose.y() + lly;
312 
313  const float gx = m_grid.idx2x(m_grid.x2idx(ggx));
314  const float gy = m_grid.idx2y(m_grid.y2idx(ggy));
315 
316  const float lx = gx - ipv.pose.x();
317  const float ly = gy - ipv.pose.y();
318 
319  poly->SetAsBox(
320  occCellSemiWidth, occCellSemiWidth, b2Vec2(lx, ly),
321  .0f /*angle*/);
322 
323  if (gl_pts && m_show_grid_collision_points)
324  {
325  gl_pts->mrpt::opengl::CPointCloud::insertPoint(
326  lx, ly, .0);
327  }
328  }
329  }
330  } // end for obj_idx
331 
332  } // end lock
333 }
const b2Shape * shape
Definition: b2Fixture.h:71
This file contains rapidxml parser and DOM implementation.
const TListBlocks & getListOfBlocks() const
Definition: World.h:183
b2Fixture * CreateFixture(const b2FixtureDef *def)
Definition: b2Body.cpp:166
std::vector< mrpt::opengl::CSetOfObjects::Ptr > m_gl_obs_clouds
Ch * value() const
Definition: rapidxml.hpp:692
mrpt::opengl::CSetOfObjects::Ptr m_gl_grid
call of gui_update()
f
std::multimap< std::string, VehicleBase * > TListVehicles
Definition: World.h:167
float32 m_radius
Definition: b2Shape.h:93
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
Definition: rapidxml.hpp:936
A 2D column vector.
Definition: b2Math.h:53
void SetTransform(const b2Vec2 &position, float32 angle)
Definition: b2Body.cpp:417
CSinCosLookUpTableFor2DScans m_sincos_lut
double m_restitution
Elastic restitution coef (default: 0.01)
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
#define SCENE_INSERT_Z_ORDER(_SCENE, _ZORDER_INDEX, _OBJ_TO_INSERT)
Definition: VisualObject.h:37
std::string resolvePath(const std::string &in_path) const
Definition: World.cpp:210
virtual void simul_pre_timestep(const TSimulContext &context)
See docs in base class.
std::multimap< std::string, Block * > TListBlocks
Definition: World.h:172
virtual void gui_update(mrpt::opengl::COpenGLScene &scene)
See docs in base class.
#define INVISIBLE_FIXTURE_USER_DATA
Used to signal a Box2D fixture as "invisible" to sensors.
Definition: basic_types.h:19
float32 density
The density, usually in kg/m^2.
Definition: b2Fixture.h:83
void SetAsBox(float32 hx, float32 hy)
COccupancyGridMap2D m_grid
const TListVehicles & getListOfVehicles() const
Definition: World.h:181
std::vector< mrpt::opengl::CPointCloud::Ptr > m_gl_obs_clouds_buffer
float32 restitution
The restitution (elasticity) usually in the range [0,1].
Definition: b2Fixture.h:80
b2World * getBox2DWorld()
Definition: World.h:178
double m_lateral_friction
(Default: 0.5)
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
See docs in base class.
std::vector< TInfoPerCollidableobj > m_obstacles_for_each_obj
std::mutex m_gl_obs_clouds_buffer_cs
float32 friction
The friction coefficient, usually in the range [0,1].
Definition: b2Fixture.h:77
b2Body * CreateBody(const b2BodyDef *def)
Definition: b2World.cpp:107


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