ElevationMap.cpp
Go to the documentation of this file.
1 /*+-------------------------------------------------------------------------+
2  | MultiVehicle simulator (libmvsim) |
3  | |
4  | Copyright (C) 2014-2020 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 <mvsim/VehicleBase.h>
11 #include <mvsim/World.h>
13 #include "xml_utils.h"
14 
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:
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  mrpt::img::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  sElevationImgFile = m_world->resolvePath(sElevationImgFile);
57 
58  mrpt::img::CImage imgElev;
59  if (!imgElev.loadFromFile(
60  sElevationImgFile, 0 /*force load grayscale*/))
61  throw std::runtime_error(mrpt::format(
62  "[ElevationMap] ERROR: Cannot read elevation image '%s'",
63  sElevationImgFile.c_str()));
64 
65  // Scale: [0,1] => [min_z,max_z]
66  // Get image normalized in range [0,1]
67  imgElev.getAsMatrix(elevation_data);
68  ASSERT_(img_min_z != img_max_z);
69 
70  const double vmin = elevation_data.minCoeff();
71  const double vmax = elevation_data.maxCoeff();
72  mrpt::math::CMatrixFloat f = elevation_data;
73  f -= vmin;
74  f *= (img_max_z - img_min_z) / (vmax - vmin);
76  elevation_data.rows(), elevation_data.cols());
77  m.setConstant(img_min_z);
78  f += m;
79  elevation_data = std::move(f);
80  }
81  else
82  {
83  MRPT_TODO("Imgs or txt matrix")
84  }
85 
86  // Load texture (optional):
87  mrpt::img::CImage mesh_image;
88  bool has_mesh_image = false;
89  if (!sTextureImgFile.empty())
90  {
91  sTextureImgFile = m_world->resolvePath(sTextureImgFile);
92 
93  if (!mesh_image.loadFromFile(sTextureImgFile))
94  throw std::runtime_error(mrpt::format(
95  "[ElevationMap] ERROR: Cannot read texture image '%s'",
96  sTextureImgFile.c_str()));
97  has_mesh_image = true;
98  }
99 
100  // Build mesh:
102 
103  m_gl_mesh->enableTransparency(false);
104 
105  if (has_mesh_image)
106  {
107  ASSERT_EQUAL_(mesh_image.getWidth(), (size_t)elevation_data.cols());
108  ASSERT_EQUAL_(mesh_image.getHeight(), (size_t)elevation_data.rows());
109 
110  m_gl_mesh->assignImageAndZ(mesh_image, 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 
128  mrpt::opengl::COpenGLScene& scene, bool childrenOnly)
129 {
130  using namespace mrpt::math;
131 
132  ASSERTMSG_(
133  m_gl_mesh,
134  "ERROR: Can't render Mesh before loading it! Have you called "
135  "loadConfigFrom() first?");
136 
137  // 1st time call?? -> Create objects
139  {
140  m_first_scene_rendering = false;
141  scene.insert(m_gl_mesh);
142  }
143 }
144 
146 {
147  // For each vehicle:
148  // 1) Compute its 3D pose according to the mesh tilt angle.
149  // 2) Apply gravity force
150  const double gravity = getWorldObject()->get_gravity();
151 
153 
154  const World::VehicleList& lstVehs = this->m_world->getListOfVehicles();
155  for (World::VehicleList::const_iterator itVeh = lstVehs.begin();
156  itVeh != lstVehs.end(); ++itVeh)
157  {
158  m_world->getTimeLogger().enter("elevationmap.handle_vehicle");
159 
160  const size_t nWheels = itVeh->second->getNumWheels();
161 
162  // 1) Compute its 3D pose according to the mesh tilt angle.
163  // Idea: run a least-squares method to find the best
164  // SE(3) transformation that map the wheels contact point,
165  // as seen in local & global coordinates.
166  // (For large tilt angles, may have to run it iteratively...)
167  // -------------------------------------------------------------
168  // the final downwards direction (unit vector (0,0,-1)) as seen in
169  // vehicle local frame.
170  mrpt::math::TPoint3D dir_down;
171  for (int iter = 0; iter < 2; iter++)
172  {
173  const mrpt::math::TPose3D& cur_pose = itVeh->second->getPose();
174  // This object is faster for repeated point projections
175  const mrpt::poses::CPose3D cur_cpose(cur_pose);
176 
177  mrpt::math::TPose3D new_pose = cur_pose;
178  corrs.clear();
179 
180  bool out_of_area = false;
181  for (size_t iW = 0; !out_of_area && iW < nWheels; iW++)
182  {
183  const Wheel& wheel = itVeh->second->getWheelInfo(iW);
184 
185  // Local frame
186  mrpt::tfest::TMatchingPair corr;
187 
188  corr.other_idx = iW;
189  corr.other_x = wheel.x;
190  corr.other_y = wheel.y;
191  corr.other_z = 0;
192 
193  // Global frame
194  const mrpt::math::TPoint3D gPt =
195  cur_cpose.composePoint({wheel.x, wheel.y, 0.0});
196  float z;
197  if (!getElevationAt(gPt.x /*in*/, gPt.y /*in*/, z /*out*/))
198  {
199  out_of_area = true;
200  continue; // vehicle is out of bounds!
201  }
202 
203  corr.this_idx = iW;
204  corr.this_x = gPt.x;
205  corr.this_y = gPt.y;
206  corr.this_z = z;
207 
208  corrs.push_back(corr);
209  }
210  if (out_of_area) continue;
211 
212  // Register:
213  double transf_scale;
215 
217  corrs, tmpl, transf_scale, true /*force scale unity*/);
218 
220  new_pose.z = m_optimal_transf.z();
221  new_pose.yaw = m_optimal_transf.yaw();
222  new_pose.pitch = m_optimal_transf.pitch();
223  new_pose.roll = m_optimal_transf.roll();
224 
225  // cout << new_pose << endl;
226 
227  itVeh->second->setPose(new_pose);
228 
229  } // end iters
230 
231  {
232  mrpt::poses::CPose3D rot_only;
234  rot_only.inverseComposePoint(
235  .0, .0, -1.0, dir_down.x, dir_down.y, dir_down.z);
236  }
237 
238  // 2) Apply gravity force
239  // -------------------------------------------------------------
240  {
241  // To chassis:
242  const double chassis_weight =
243  itVeh->second->getChassisMass() * gravity;
244  const mrpt::math::TPoint2D chassis_com =
245  itVeh->second->getChassisCenterOfMass();
246  itVeh->second->apply_force(
247  {dir_down.x * chassis_weight, dir_down.y * chassis_weight},
248  chassis_com);
249 
250  // To wheels:
251  for (size_t iW = 0; iW < nWheels; iW++)
252  {
253  const Wheel& wheel = itVeh->second->getWheelInfo(iW);
254  const double wheel_weight = wheel.mass * gravity;
255  itVeh->second->apply_force(
256  {dir_down.x * wheel_weight, dir_down.y * wheel_weight},
257  {wheel.x, wheel.y});
258  }
259  }
260 
261  m_world->getTimeLogger().leave("elevationmap.handle_vehicle");
262  }
263 }
264 
266 {
268 
269  MRPT_TODO(
270  "Save all elements positions in prestep, then here scale their "
271  "movements * cos(angle)");
272 }
273 
274 static float calcz(
275  const mrpt::math::TPoint3Df& p1, const mrpt::math::TPoint3Df& p2,
276  const mrpt::math::TPoint3Df& p3, float x, float y)
277 {
278  const float det =
279  (p2.x - p3.x) * (p1.y - p3.y) + (p3.y - p2.y) * (p1.x - p3.x);
280  ASSERT_(det != 0.0f);
281 
282  const float l1 =
283  ((p2.x - p3.x) * (y - p3.y) + (p3.y - p2.y) * (x - p3.x)) / det;
284  const float l2 =
285  ((p3.x - p1.x) * (y - p3.y) + (p1.y - p3.y) * (x - p3.x)) / det;
286  const float l3 = 1.0f - l1 - l2;
287 
288  return l1 * p1.z + l2 * p2.z + l3 * p3.z;
289 }
290 
291 bool ElevationMap::getElevationAt(double x, double y, float& z) const
292 {
293  const mrpt::opengl::CMesh* mesh = m_gl_mesh.get();
294  const float x0 = mesh->getxMin();
295  const float y0 = mesh->getyMin();
296  const size_t nCellsX = m_mesh_z_cache.cols();
297  const size_t nCellsY = m_mesh_z_cache.rows();
298 
299  // Discretize:
300  const int cx00 = ::floor((x - x0) / m_resolution);
301  const int cy00 = ::floor((y - y0) / m_resolution);
302 
303  if (cx00 < 1 || cx00 >= int(nCellsX - 1) || cy00 < 1 ||
304  cy00 >= int(nCellsY - 1))
305  return false;
306 
307  // Linear interpolation:
308  const float z00 = m_mesh_z_cache(cy00, cx00);
309  const float z01 = m_mesh_z_cache(cy00 + 1, cx00);
310  const float z10 = m_mesh_z_cache(cy00, cx00 + 1);
311  const float z11 = m_mesh_z_cache(cy00 + 1, cx00 + 1);
312 
313  //
314  // p01 ---- p11
315  // | |
316  // p00 ---- p10
317  //
318  const mrpt::math::TPoint3Df p00(.0f, .0f, z00);
319  const mrpt::math::TPoint3Df p01(.0f, m_resolution, z01);
320  const mrpt::math::TPoint3Df p10(m_resolution, .0f, z10);
322 
323  const float lx = x - (x0 + cx00 * m_resolution);
324  const float ly = y - (y0 + cy00 * m_resolution);
325 
326  if (ly >= lx)
327  z = calcz(p00, p01, p11, lx, ly);
328  else
329  z = calcz(p00, p10, p11, lx, ly);
330 
331  return true;
332 }
#define ASSERT_EQUAL_(__A, __B)
This file contains rapidxml parser and DOM implementation.
GLint GLint GLint GLint GLint GLint y
std::map< std::string, TParamEntry > TParameterDefinitions
mrpt::tfest::TMatchingPairList corrs
Definition: ElevationMap.h:51
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root) override
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="")
Definition: xml_utils.cpp:179
const VehicleList & getListOfVehicles() const
Definition: World.h:195
virtual void simul_pre_timestep(const TSimulContext &context) override
static CMeshPtr Create(bool enableTransparency, float xMin=0.0f, float xMax=0.0f, float yMin=0.0f, float yMax=0.0f)
double roll() const
std::multimap< std::string, VehicleBase::Ptr > VehicleList
Definition: World.h:173
void insert(const CRenderizablePtr &newObject, const std::string &viewportName=std::string("main"))
MRPT_TODO("Modify ping to run on Windows + Test this")
double get_gravity() const
Definition: World.h:82
double x
Definition: Wheel.h:36
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL, bool use_small_rot_approx=false) const
virtual void internalGuiUpdate(mrpt::opengl::COpenGLScene &scene, bool childrenOnly) override
World * getWorldObject()
Definition: VisualObject.h:34
double yaw() const
std::string resolvePath(const std::string &in_path) const
Definition: World.cpp:162
GLint GLint GLint GLint GLint x
double y
Definition: Wheel.h:36
bool TFEST_IMPEXP se3_l2(const mrpt::utils::TMatchingPairList &in_correspondences, mrpt::poses::CPose3DQuat &out_transform, double &out_scale, bool forceScaleToUnity=false)
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
double pitch() const
virtual void simul_post_timestep(const TSimulContext &context)
Definition: Simulable.cpp:38
static float calcz(const mrpt::math::TPoint3Df &p1, const mrpt::math::TPoint3Df &p2, const mrpt::math::TPoint3Df &p3, float x, float y)
GLdouble GLdouble z
mrpt::opengl::CMesh::Ptr m_gl_mesh
Definition: ElevationMap.h:43
mrpt::system::CTimeLogger & getTimeLogger()
Definition: World.h:210
double mass
[kg]
Definition: Wheel.h:40
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
#define ASSERT_(f)
GLfloat * params
mrpt::math::CMatrixFloat m_mesh_z_cache
Definition: ElevationMap.h:47
const GLdouble * m
void inverseComposePoint(const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL) const
bool getElevationAt(double x, double y, float &z) const
return false if out of bounds
#define ASSERTMSG_(f, __ERROR_MSG)
EIGEN_STRONG_INLINE Scalar det() const
virtual void simul_post_timestep(const TSimulContext &context) override
void setRotationMatrix(const mrpt::math::CMatrixDouble33 &ROT)
mrpt::poses::CPose3D m_optimal_transf
Definition: ElevationMap.h:52
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f


mvsim
Author(s):
autogenerated on Fri May 7 2021 03:05:51