ElevationMap.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 <mvsim/VehicleBase.h>
13 #include "xml_utils.h"
14 
15 #include <mrpt/opengl/COpenGLScene.h>
16 #include <mrpt/opengl/CPointCloud.h>
17 #include <mrpt/tfest.h> // least-squares methods
18 #include <rapidxml.hpp>
19 
20 using namespace rapidxml;
21 using namespace mvsim;
22 using namespace std;
23 
24 ElevationMap::ElevationMap(World* parent, const rapidxml::xml_node<char>* root)
25  : WorldElementBase(parent), m_first_scene_rendering(true), m_resolution(1.0)
26 {
27  loadConfigFrom(root);
28 }
29 
32 {
33  // Other general params:
34  std::map<std::string, TParamEntry> params;
35 
36  std::string sElevationImgFile;
37  params["elevation_image"] = TParamEntry("%s", &sElevationImgFile);
38  std::string sTextureImgFile;
39  params["texture_image"] = TParamEntry("%s", &sTextureImgFile);
40 
41  double img_min_z = 0.0, img_max_z = 5.0;
42  params["elevation_image_min_z"] = TParamEntry("%lf", &img_min_z);
43  params["elevation_image_max_z"] = TParamEntry("%lf", &img_max_z);
44 
45  TColor mesh_color(0xa0, 0xe0, 0xa0);
46  params["mesh_color"] = TParamEntry("%color", &mesh_color);
47 
48  params["resolution"] = TParamEntry("%lf", &m_resolution);
49 
50  parse_xmlnode_children_as_param(*root, params);
51 
52  // Load elevation data:
53  mrpt::math::CMatrixFloat elevation_data;
54  if (!sElevationImgFile.empty())
55  {
56  CImage imgElev;
57  if (!imgElev.loadFromFile(
58  sElevationImgFile, 0 /*force load grayscale*/))
59  throw std::runtime_error(mrpt::format(
60  "[ElevationMap] ERROR: Cannot read elevation image '%s'",
61  sElevationImgFile.c_str()));
62 
63  // Scale: [0,1] => [min_z,max_z]
64  imgElev.getAsMatrix(
65  elevation_data); // Get image normalized in range [0,1]
66  ASSERT_(img_min_z != img_max_z);
67 #if MRPT_VERSION >= 0x199
68  const double vmin = elevation_data.minCoeff();
69  const double vmax = elevation_data.maxCoeff();
70  mrpt::math::CMatrixFloat f = elevation_data;
71  f -= vmin;
72  f *= (img_max_z - img_min_z) / (vmax - vmin);
73  mrpt::math::CMatrixFloat m(
74  elevation_data.rows(), elevation_data.cols());
75  m.setConstant(img_min_z);
76  f += m;
77  elevation_data = f;
78 #else
79  elevation_data.adjustRange(img_min_z, img_max_z);
80 #endif
81  }
82  else
83  {
84  MRPT_TODO("Imgs or txt matrix")
85  }
86 
87  // Load texture (optional):
88  CImage mesh_image;
89  bool has_mesh_image = false;
90  if (!sTextureImgFile.empty())
91  {
92  if (!mesh_image.loadFromFile(sTextureImgFile))
93  throw std::runtime_error(mrpt::format(
94  "[ElevationMap] ERROR: Cannot read texture image '%s'",
95  sTextureImgFile.c_str()));
96  has_mesh_image = true;
97  }
98 
99  // Build mesh:
100  m_gl_mesh = mrpt::opengl::CMesh::Create();
101 
102  m_gl_mesh->enableTransparency(false);
103 
104  if (has_mesh_image)
105  {
106  ASSERT_EQUAL_(mesh_image.getWidth(), (size_t)elevation_data.cols());
107  ASSERT_EQUAL_(mesh_image.getHeight(), (size_t)elevation_data.rows());
108 
109  m_gl_mesh->assignImage(mesh_image);
110  m_gl_mesh->setZ(elevation_data);
111  }
112  else
113  {
114  m_gl_mesh->setZ(elevation_data);
115  m_gl_mesh->setColor_u8(mesh_color);
116  }
117 
118  // Save copy for calcs:
119  m_mesh_z_cache = elevation_data;
120 
121  // Extension: X,Y
122  const double LX = (elevation_data.cols() - 1) * m_resolution;
123  const double LY = (elevation_data.rows() - 1) * m_resolution;
124  m_gl_mesh->setGridLimits(-0.5 * LX, 0.5 * LX, -0.5 * LY, 0.5 * LY);
125 }
126 
127 void ElevationMap::gui_update(mrpt::opengl::COpenGLScene& scene)
128 {
129  using namespace mrpt::math;
130 
131  ASSERTMSG_(
132  m_gl_mesh,
133  "ERROR: Can't render Mesh before loading it! Have you called "
134  "loadConfigFrom() first?");
135 
136  // 1st time call?? -> Create objects
138  {
139  m_first_scene_rendering = false;
140  SCENE_INSERT_Z_ORDER(scene, 0, m_gl_mesh);
141  }
142 }
143 
145 {
146  // For each vehicle:
147  // 1) Compute its 3D pose according to the mesh tilt angle.
148  // 2) Apply gravity force
149  const double gravity = getWorldObject()->get_gravity();
150 
151  ASSERT_(m_gl_mesh);
152 
153  const World::TListVehicles& lstVehs = this->m_world->getListOfVehicles();
154  for (World::TListVehicles::const_iterator itVeh = lstVehs.begin();
155  itVeh != lstVehs.end(); ++itVeh)
156  {
157  m_world->getTimeLogger().enter("elevationmap.handle_vehicle");
158 
159  const size_t nWheels = itVeh->second->getNumWheels();
160 
161  // 1) Compute its 3D pose according to the mesh tilt angle.
162  // Idea: run a least-squares method to find the best
163  // SE(3) transformation that map the wheels contact point,
164  // as seen in local & global coordinates.
165  // (For large tilt angles, may have to run it iteratively...)
166  // -------------------------------------------------------------
167  mrpt::math::TPoint3D dir_down; // the final downwards direction (unit
168  // vector (0,0,-1)) as seen in vehicle
169  // local frame.
170  for (int iter = 0; iter < 3; iter++)
171  {
172  const mrpt::math::TPose3D& cur_pose = itVeh->second->getPose();
173  const mrpt::poses::CPose3D cur_cpose(cur_pose); // This object is
174  // faster for
175  // repeated point
176  // projections
177 
178  mrpt::math::TPose3D new_pose = cur_pose;
179 
180  // See mrpt::scanmatching::leastSquareErrorRigidTransformation6D()
181  // docs
182  corrs.clear();
183 
184  bool out_of_area = false;
185  for (size_t iW = 0; !out_of_area && iW < nWheels; iW++)
186  {
187  const Wheel& wheel = itVeh->second->getWheelInfo(iW);
188 
189  // Local frame
190  TMatchingPair corr;
191 
192  corr.other_idx = iW;
193  corr.other_x = wheel.x;
194  corr.other_y = wheel.y;
195  corr.other_z = 0;
196 
197  // Global frame
198  mrpt::math::TPoint3D gPt;
199  cur_cpose.composePoint(
200  wheel.x, wheel.y, 0.0, gPt.x, gPt.y, gPt.z);
201  float z;
202  if (!getElevationAt(gPt.x /*in*/, gPt.y /*in*/, z /*out*/))
203  {
204  out_of_area = true;
205  continue; // vehicle is out of bounds!
206  }
207 
208  corr.this_idx = iW;
209  corr.this_x = gPt.x;
210  corr.this_y = gPt.y;
211  corr.this_z = z;
212 
213  corrs.push_back(corr);
214  }
215  if (out_of_area) continue;
216 
217  // Register:
218  double transf_scale;
219  mrpt::poses::CPose3DQuat tmpl;
220 
221  mrpt::tfest::se3_l2(
222  corrs, tmpl, transf_scale, true /*force scale unity*/);
223 
224  m_optimal_transf = mrpt::poses::CPose3D(tmpl);
225  new_pose.z = m_optimal_transf.z();
226  new_pose.yaw = m_optimal_transf.yaw();
227  new_pose.pitch = m_optimal_transf.pitch();
228  new_pose.roll = m_optimal_transf.roll();
229 
230  // cout << new_pose << endl;
231 
232  itVeh->second->setPose(new_pose);
233 
234  } // end iters
235 
236  {
237  mrpt::poses::CPose3D rot_only;
238  rot_only.setRotationMatrix(m_optimal_transf.getRotationMatrix());
239  rot_only.inverseComposePoint(
240  .0, .0, -1.0, dir_down.x, dir_down.y, dir_down.z);
241  }
242 
243  // 2) Apply gravity force
244  // -------------------------------------------------------------
245  {
246  // To chassis:
247  const double chassis_weight =
248  itVeh->second->getChassisMass() * gravity;
249  const mrpt::math::TPoint2D chassis_com =
250  itVeh->second->getChassisCenterOfMass();
251  itVeh->second->apply_force(
252  dir_down.x * chassis_weight, dir_down.y * chassis_weight,
253  chassis_com.x, chassis_com.y);
254 
255  // To wheels:
256  for (size_t iW = 0; iW < nWheels; iW++)
257  {
258  const Wheel& wheel = itVeh->second->getWheelInfo(iW);
259  const double wheel_weight = wheel.mass * gravity;
260  itVeh->second->apply_force(
261  dir_down.x * wheel_weight, dir_down.y * wheel_weight,
262  wheel.x, wheel.y);
263  }
264  }
265 
266  m_world->getTimeLogger().leave("elevationmap.handle_vehicle");
267  }
268 }
269 
271 {
272  MRPT_TODO(
273  "Save all elements positions in prestep, then here scale their "
274  "movements * cos(angle)");
275 }
276 float calcz(
277  const mrpt::math::TPoint3Df& p1, const mrpt::math::TPoint3Df& p2,
278  const mrpt::math::TPoint3Df& p3, float x, float y)
279 {
280  const float det =
281  (p2.x - p3.x) * (p1.y - p3.y) + (p3.y - p2.y) * (p1.x - p3.x);
282  ASSERT_(det != 0.0f);
283 
284  const float l1 =
285  ((p2.x - p3.x) * (y - p3.y) + (p3.y - p2.y) * (x - p3.x)) / det;
286  const float l2 =
287  ((p3.x - p1.x) * (y - p3.y) + (p1.y - p3.y) * (x - p3.x)) / det;
288  const float l3 = 1.0f - l1 - l2;
289 
290  return l1 * p1.z + l2 * p2.z + l3 * p3.z;
291 }
292 
293 bool ElevationMap::getElevationAt(double x, double y, float& z) const
294 {
295  const mrpt::opengl::CMesh* mesh = m_gl_mesh.get();
296  const float x0 = mesh->getXMin();
297  const float y0 = mesh->getYMin();
298  const size_t nCellsX = m_mesh_z_cache.rows();
299  const size_t nCellsY = m_mesh_z_cache.cols();
300 
301  // Discretize:
302  const int cx00 = ::floor((x - x0) / m_resolution);
303  const int cy00 = ::floor((y - y0) / m_resolution);
304  if (cx00 < 1 || cx00 >= int(nCellsX - 1) || cy00 < 1 ||
305  cy00 >= int(nCellsY - 1))
306  return false;
307 
308  // Linear interpolation:
309  const float z00 = m_mesh_z_cache(cx00, cy00);
310  const float z01 = m_mesh_z_cache(cx00, cy00 + 1);
311  const float z10 = m_mesh_z_cache(cx00 + 1, cy00);
312  const float z11 = m_mesh_z_cache(cx00 + 1, cy00 + 1);
313 
314  //
315  // p01 ---- p11
316  // | |
317  // p00 ---- p10
318  //
319  const mrpt::math::TPoint3Df p00(.0f, .0f, z00);
320  const mrpt::math::TPoint3Df p01(.0f, m_resolution, z01);
321  const mrpt::math::TPoint3Df p10(m_resolution, .0f, z10);
322  const mrpt::math::TPoint3Df p11(m_resolution, m_resolution, z11);
323 
324  const float lx = x - (x0 + cx00 * m_resolution);
325  const float ly = y - (y0 + cy00 * m_resolution);
326 
327  if (ly >= lx)
328  z = calcz(p00, p01, p11, lx, ly);
329  else
330  z = calcz(p00, p10, p11, lx, ly);
331 
332  return true;
333 }
virtual void simul_pre_timestep(const TSimulContext &context)
See docs in base class.
This file contains rapidxml parser and DOM implementation.
virtual void gui_update(mrpt::opengl::COpenGLScene &scene)
See docs in base class.
f
TMatchingPairList corrs
Definition: ElevationMap.h:66
std::multimap< std::string, VehicleBase * > TListVehicles
Definition: World.h:167
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.
double get_gravity() const
Definition: World.h:113
double x
Definition: Wheel.h:41
CTimeLogger & getTimeLogger()
Definition: World.h:190
World * getWorldObject()
Definition: VisualObject.h:29
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
double y
Definition: Wheel.h:41
TFSIMD_FORCE_INLINE const tfScalar & z() const
mrpt::opengl::CMesh::Ptr m_gl_mesh
Definition: ElevationMap.h:57
double mass
[kg]
Definition: Wheel.h:45
const TListVehicles & getListOfVehicles() const
Definition: World.h:181
mrpt::math::CMatrixFloat m_mesh_z_cache
Definition: ElevationMap.h:60
bool getElevationAt(double x, double y, float &z) const
return false if out of bounds
float calcz(const mrpt::math::TPoint3Df &p1, const mrpt::math::TPoint3Df &p2, const mrpt::math::TPoint3Df &p3, float x, float y)
mrpt::poses::CPose3D m_optimal_transf
Definition: ElevationMap.h:67


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