ElevationMap.cpp
Go to the documentation of this file.
00001 /*+-------------------------------------------------------------------------+
00002   |                       MultiVehicle simulator (libmvsim)                 |
00003   |                                                                         |
00004   | Copyright (C) 2014  Jose Luis Blanco Claraco (University of Almeria)    |
00005   | Copyright (C) 2017  Borys Tymchenko (Odessa Polytechnic University)     |
00006   | Distributed under GNU General Public License version 3                  |
00007   |   See <http://www.gnu.org/licenses/>                                    |
00008   +-------------------------------------------------------------------------+ */
00009 
00010 #include <mvsim/WorldElements/ElevationMap.h>
00011 #include <mvsim/World.h>
00012 #include <mvsim/VehicleBase.h>
00013 #include "xml_utils.h"
00014 
00015 #include <mrpt/opengl/COpenGLScene.h>
00016 #include <mrpt/opengl/CPointCloud.h>
00017 #include <mrpt/tfest.h>  // least-squares methods
00018 #include <rapidxml.hpp>
00019 
00020 using namespace rapidxml;
00021 using namespace mvsim;
00022 using namespace std;
00023 
00024 ElevationMap::ElevationMap(World* parent, const rapidxml::xml_node<char>* root)
00025         : WorldElementBase(parent), m_first_scene_rendering(true), m_resolution(1.0)
00026 {
00027         loadConfigFrom(root);
00028 }
00029 
00030 ElevationMap::~ElevationMap() {}
00031 void ElevationMap::loadConfigFrom(const rapidxml::xml_node<char>* root)
00032 {
00033         // Other general params:
00034         std::map<std::string, TParamEntry> params;
00035 
00036         std::string sElevationImgFile;
00037         params["elevation_image"] = TParamEntry("%s", &sElevationImgFile);
00038         std::string sTextureImgFile;
00039         params["texture_image"] = TParamEntry("%s", &sTextureImgFile);
00040 
00041         double img_min_z = 0.0, img_max_z = 5.0;
00042         params["elevation_image_min_z"] = TParamEntry("%lf", &img_min_z);
00043         params["elevation_image_max_z"] = TParamEntry("%lf", &img_max_z);
00044 
00045         TColor mesh_color(0xa0, 0xe0, 0xa0);
00046         params["mesh_color"] = TParamEntry("%color", &mesh_color);
00047 
00048         params["resolution"] = TParamEntry("%lf", &m_resolution);
00049 
00050         parse_xmlnode_children_as_param(*root, params);
00051 
00052         // Load elevation data:
00053         mrpt::math::CMatrixFloat elevation_data;
00054         if (!sElevationImgFile.empty())
00055         {
00056                 CImage imgElev;
00057                 if (!imgElev.loadFromFile(
00058                                 sElevationImgFile, 0 /*force load grayscale*/))
00059                         throw std::runtime_error(mrpt::format(
00060                                 "[ElevationMap] ERROR: Cannot read elevation image '%s'",
00061                                 sElevationImgFile.c_str()));
00062 
00063                 // Scale: [0,1] => [min_z,max_z]
00064                 imgElev.getAsMatrix(
00065                         elevation_data);  // Get image normalized in range [0,1]
00066                 ASSERT_(img_min_z != img_max_z);
00067 #if MRPT_VERSION >= 0x199
00068                 const double vmin = elevation_data.minCoeff();
00069                 const double vmax = elevation_data.maxCoeff();
00070                 mrpt::math::CMatrixFloat f = elevation_data;
00071                 f -= vmin;
00072                 f *= (img_max_z - img_min_z) / (vmax - vmin);
00073                 mrpt::math::CMatrixFloat m(
00074                         elevation_data.rows(), elevation_data.cols());
00075                 m.setConstant(img_min_z);
00076                 f += m;
00077                 elevation_data = f;
00078 #else
00079                 elevation_data.adjustRange(img_min_z, img_max_z);
00080 #endif
00081         }
00082         else
00083         {
00084                 MRPT_TODO("Imgs or txt matrix")
00085         }
00086 
00087         // Load texture (optional):
00088         CImage mesh_image;
00089         bool has_mesh_image = false;
00090         if (!sTextureImgFile.empty())
00091         {
00092                 if (!mesh_image.loadFromFile(sTextureImgFile))
00093                         throw std::runtime_error(mrpt::format(
00094                                 "[ElevationMap] ERROR: Cannot read texture image '%s'",
00095                                 sTextureImgFile.c_str()));
00096                 has_mesh_image = true;
00097         }
00098 
00099         // Build mesh:
00100         m_gl_mesh = mrpt::opengl::CMesh::Create();
00101 
00102         m_gl_mesh->enableTransparency(false);
00103 
00104         if (has_mesh_image)
00105         {
00106                 ASSERT_EQUAL_(mesh_image.getWidth(), (size_t)elevation_data.cols());
00107                 ASSERT_EQUAL_(mesh_image.getHeight(), (size_t)elevation_data.rows());
00108 
00109                 m_gl_mesh->assignImage(mesh_image);
00110                 m_gl_mesh->setZ(elevation_data);
00111         }
00112         else
00113         {
00114                 m_gl_mesh->setZ(elevation_data);
00115                 m_gl_mesh->setColor_u8(mesh_color);
00116         }
00117 
00118         // Save copy for calcs:
00119         m_mesh_z_cache = elevation_data;
00120 
00121         // Extension: X,Y
00122         const double LX = (elevation_data.cols() - 1) * m_resolution;
00123         const double LY = (elevation_data.rows() - 1) * m_resolution;
00124         m_gl_mesh->setGridLimits(-0.5 * LX, 0.5 * LX, -0.5 * LY, 0.5 * LY);
00125 }
00126 
00127 void ElevationMap::gui_update(mrpt::opengl::COpenGLScene& scene)
00128 {
00129         using namespace mrpt::math;
00130 
00131         ASSERTMSG_(
00132                 m_gl_mesh,
00133                 "ERROR: Can't render Mesh before loading it! Have you called "
00134                 "loadConfigFrom() first?");
00135 
00136         // 1st time call?? -> Create objects
00137         if (m_first_scene_rendering)
00138         {
00139                 m_first_scene_rendering = false;
00140                 SCENE_INSERT_Z_ORDER(scene, 0, m_gl_mesh);
00141         }
00142 }
00143 
00144 void ElevationMap::simul_pre_timestep(const TSimulContext& context)
00145 {
00146         // For each vehicle:
00147         // 1) Compute its 3D pose according to the mesh tilt angle.
00148         // 2) Apply gravity force
00149         const double gravity = getWorldObject()->get_gravity();
00150 
00151         ASSERT_(m_gl_mesh);
00152 
00153         const World::TListVehicles& lstVehs = this->m_world->getListOfVehicles();
00154         for (World::TListVehicles::const_iterator itVeh = lstVehs.begin();
00155                  itVeh != lstVehs.end(); ++itVeh)
00156         {
00157                 m_world->getTimeLogger().enter("elevationmap.handle_vehicle");
00158 
00159                 const size_t nWheels = itVeh->second->getNumWheels();
00160 
00161                 // 1) Compute its 3D pose according to the mesh tilt angle.
00162                 // Idea: run a least-squares method to find the best
00163                 // SE(3) transformation that map the wheels contact point,
00164                 // as seen in local & global coordinates.
00165                 // (For large tilt angles, may have to run it iteratively...)
00166                 // -------------------------------------------------------------
00167                 mrpt::math::TPoint3D dir_down;  // the final downwards direction (unit
00168                                                                                 // vector (0,0,-1)) as seen in vehicle
00169                                                                                 // local frame.
00170                 for (int iter = 0; iter < 3; iter++)
00171                 {
00172                         const mrpt::math::TPose3D& cur_pose = itVeh->second->getPose();
00173                         const mrpt::poses::CPose3D cur_cpose(cur_pose);  // This object is
00174                                                                                                                          // faster for
00175                                                                                                                          // repeated point
00176                                                                                                                          // projections
00177 
00178                         mrpt::math::TPose3D new_pose = cur_pose;
00179 
00180                         // See mrpt::scanmatching::leastSquareErrorRigidTransformation6D()
00181                         // docs
00182                         corrs.clear();
00183 
00184                         bool out_of_area = false;
00185                         for (size_t iW = 0; !out_of_area && iW < nWheels; iW++)
00186                         {
00187                                 const Wheel& wheel = itVeh->second->getWheelInfo(iW);
00188 
00189                                 // Local frame
00190                                 TMatchingPair corr;
00191 
00192                                 corr.other_idx = iW;
00193                                 corr.other_x = wheel.x;
00194                                 corr.other_y = wheel.y;
00195                                 corr.other_z = 0;
00196 
00197                                 // Global frame
00198                                 mrpt::math::TPoint3D gPt;
00199                                 cur_cpose.composePoint(
00200                                         wheel.x, wheel.y, 0.0, gPt.x, gPt.y, gPt.z);
00201                                 float z;
00202                                 if (!getElevationAt(gPt.x /*in*/, gPt.y /*in*/, z /*out*/))
00203                                 {
00204                                         out_of_area = true;
00205                                         continue;  // vehicle is out of bounds!
00206                                 }
00207 
00208                                 corr.this_idx = iW;
00209                                 corr.this_x = gPt.x;
00210                                 corr.this_y = gPt.y;
00211                                 corr.this_z = z;
00212 
00213                                 corrs.push_back(corr);
00214                         }
00215                         if (out_of_area) continue;
00216 
00217                         // Register:
00218                         double transf_scale;
00219                         mrpt::poses::CPose3DQuat tmpl;
00220 
00221                         mrpt::tfest::se3_l2(
00222                                 corrs, tmpl, transf_scale, true /*force scale unity*/);
00223 
00224                         m_optimal_transf = mrpt::poses::CPose3D(tmpl);
00225                         new_pose.z = m_optimal_transf.z();
00226                         new_pose.yaw = m_optimal_transf.yaw();
00227                         new_pose.pitch = m_optimal_transf.pitch();
00228                         new_pose.roll = m_optimal_transf.roll();
00229 
00230                         // cout << new_pose << endl;
00231 
00232                         itVeh->second->setPose(new_pose);
00233 
00234                 }  // end iters
00235 
00236                 {
00237                         mrpt::poses::CPose3D rot_only;
00238                         rot_only.setRotationMatrix(m_optimal_transf.getRotationMatrix());
00239                         rot_only.inverseComposePoint(
00240                                 .0, .0, -1.0, dir_down.x, dir_down.y, dir_down.z);
00241                 }
00242 
00243                 // 2) Apply gravity force
00244                 // -------------------------------------------------------------
00245                 {
00246                         // To chassis:
00247                         const double chassis_weight =
00248                                 itVeh->second->getChassisMass() * gravity;
00249                         const mrpt::math::TPoint2D chassis_com =
00250                                 itVeh->second->getChassisCenterOfMass();
00251                         itVeh->second->apply_force(
00252                                 dir_down.x * chassis_weight, dir_down.y * chassis_weight,
00253                                 chassis_com.x, chassis_com.y);
00254 
00255                         // To wheels:
00256                         for (size_t iW = 0; iW < nWheels; iW++)
00257                         {
00258                                 const Wheel& wheel = itVeh->second->getWheelInfo(iW);
00259                                 const double wheel_weight = wheel.mass * gravity;
00260                                 itVeh->second->apply_force(
00261                                         dir_down.x * wheel_weight, dir_down.y * wheel_weight,
00262                                         wheel.x, wheel.y);
00263                         }
00264                 }
00265 
00266                 m_world->getTimeLogger().leave("elevationmap.handle_vehicle");
00267         }
00268 }
00269 
00270 void ElevationMap::simul_post_timestep(const TSimulContext& context)
00271 {
00272         MRPT_TODO(
00273                 "Save all elements positions in prestep, then here scale their "
00274                 "movements * cos(angle)");
00275 }
00276 float calcz(
00277         const mrpt::math::TPoint3Df& p1, const mrpt::math::TPoint3Df& p2,
00278         const mrpt::math::TPoint3Df& p3, float x, float y)
00279 {
00280         const float det =
00281                 (p2.x - p3.x) * (p1.y - p3.y) + (p3.y - p2.y) * (p1.x - p3.x);
00282         ASSERT_(det != 0.0f);
00283 
00284         const float l1 =
00285                 ((p2.x - p3.x) * (y - p3.y) + (p3.y - p2.y) * (x - p3.x)) / det;
00286         const float l2 =
00287                 ((p3.x - p1.x) * (y - p3.y) + (p1.y - p3.y) * (x - p3.x)) / det;
00288         const float l3 = 1.0f - l1 - l2;
00289 
00290         return l1 * p1.z + l2 * p2.z + l3 * p3.z;
00291 }
00292 
00293 bool ElevationMap::getElevationAt(double x, double y, float& z) const
00294 {
00295         const mrpt::opengl::CMesh* mesh = m_gl_mesh.get();
00296         const float x0 = mesh->getXMin();
00297         const float y0 = mesh->getYMin();
00298         const size_t nCellsX = m_mesh_z_cache.rows();
00299         const size_t nCellsY = m_mesh_z_cache.cols();
00300 
00301         // Discretize:
00302         const int cx00 = ::floor((x - x0) / m_resolution);
00303         const int cy00 = ::floor((y - y0) / m_resolution);
00304         if (cx00 < 1 || cx00 >= int(nCellsX - 1) || cy00 < 1 ||
00305                 cy00 >= int(nCellsY - 1))
00306                 return false;
00307 
00308         // Linear interpolation:
00309         const float z00 = m_mesh_z_cache(cx00, cy00);
00310         const float z01 = m_mesh_z_cache(cx00, cy00 + 1);
00311         const float z10 = m_mesh_z_cache(cx00 + 1, cy00);
00312         const float z11 = m_mesh_z_cache(cx00 + 1, cy00 + 1);
00313 
00314         //
00315         //   p01 ---- p11
00316         //    |        |
00317         //   p00 ---- p10
00318         //
00319         const mrpt::math::TPoint3Df p00(.0f, .0f, z00);
00320         const mrpt::math::TPoint3Df p01(.0f, m_resolution, z01);
00321         const mrpt::math::TPoint3Df p10(m_resolution, .0f, z10);
00322         const mrpt::math::TPoint3Df p11(m_resolution, m_resolution, z11);
00323 
00324         const float lx = x - (x0 + cx00 * m_resolution);
00325         const float ly = y - (y0 + cy00 * m_resolution);
00326 
00327         if (ly >= lx)
00328                 z = calcz(p00, p01, p11, lx, ly);
00329         else
00330                 z = calcz(p00, p10, p11, lx, ly);
00331 
00332         return true;
00333 }


mvsim
Author(s):
autogenerated on Thu Jun 6 2019 22:08:35