OccupancyGridMap.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/OccupancyGridMap.h>
00011 #include <mvsim/World.h>
00012 #include "xml_utils.h"
00013 
00014 #include <mrpt/opengl/COpenGLScene.h>
00015 #include <mrpt/poses/CPose2D.h>
00016 #include <mrpt/utils/CFileGZInputStream.h>
00017 #include <mrpt/system/filesystem.h>
00018 #include <mrpt/utils/CObject.h>
00019 #include <rapidxml.hpp>
00020 
00021 #include <mrpt/version.h>
00022 #if MRPT_VERSION >= 0x130
00023 #include <mrpt/maps/CSimplePointsMap.h>
00024 using mrpt::maps::CSimplePointsMap;
00025 #else
00026 #include <mrpt/slam/CSimplePointsMap.h>
00027 using mrpt::slam::CSimplePointsMap;
00028 #endif
00029 
00030 using namespace rapidxml;
00031 using namespace mvsim;
00032 using namespace std;
00033 
00034 OccupancyGridMap::OccupancyGridMap(
00035         World* parent, const rapidxml::xml_node<char>* root)
00036         : WorldElementBase(parent),
00037           m_gui_uptodate(false),
00038           m_show_grid_collision_points(true),
00039           m_restitution(0.01),
00040           m_lateral_friction(0.5)
00041 {
00042         loadConfigFrom(root);
00043 }
00044 
00045 OccupancyGridMap::~OccupancyGridMap() {}
00046 void OccupancyGridMap::loadConfigFrom(const rapidxml::xml_node<char>* root)
00047 {
00048         m_gui_uptodate = false;
00049 
00050         // <file>FILENAME.{png,gridmap}</file>
00051         xml_node<>* xml_file = root->first_node("file");
00052         if (!xml_file || !xml_file->value())
00053                 throw std::runtime_error(
00054                         "Error: <file></file> XML entry not found inside gridmap node!");
00055 
00056         const string sFile = m_world->resolvePath(xml_file->value());
00057         const string sFileExt =
00058                 mrpt::system::extractFileExtension(sFile, true /*ignore gz*/);
00059 
00060         // MRPT gridmaps format:
00061         if (sFileExt == "gridmap")
00062         {
00063                 mrpt::utils::CFileGZInputStream f(sFile);
00064                 f >> m_grid;
00065         }
00066         else
00067         // Assume it's an image:
00068         {
00069                 std::map<std::string, TParamEntry> other_params;
00070                 double xcenterpixel = -1, ycenterpixel = -1;
00071                 double resolution = 0.10;
00072 
00073                 other_params["resolution"] = TParamEntry("%lf", &resolution);
00074                 other_params["centerpixel_x"] = TParamEntry("%lf", &xcenterpixel);
00075                 other_params["centerpixel_y"] = TParamEntry("%lf", &ycenterpixel);
00076 
00077                 parse_xmlnode_children_as_param(*root, other_params);
00078 
00079                 if (!m_grid.loadFromBitmapFile(
00080                                 sFile, resolution, xcenterpixel, ycenterpixel))
00081                         throw std::runtime_error(
00082                                 mrpt::format(
00083                                         "[OccupancyGridMap] ERROR: File not found '%s'",
00084                                         sFile.c_str()));
00085         }
00086 
00087         {
00088                 // Other general params:
00089                 std::map<std::string, TParamEntry> ps;
00090                 ps["show_collisions"] =
00091                         TParamEntry("%bool", &m_show_grid_collision_points);
00092                 ps["restitution"] = TParamEntry("%lf", &m_restitution);
00093                 ps["lateral_friction"] = TParamEntry("%lf", &m_lateral_friction);
00094 
00095                 parse_xmlnode_children_as_param(*root, ps);
00096         }
00097 }
00098 
00099 void OccupancyGridMap::gui_update(mrpt::opengl::COpenGLScene& scene)
00100 {
00101         using namespace mrpt::math;
00102 
00103         // 1st time call?? -> Create objects
00104         if (!m_gl_grid)
00105         {
00106                 m_gl_grid = mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
00107                 SCENE_INSERT_Z_ORDER(scene, 0, m_gl_grid);
00108         }
00109         if (m_gl_obs_clouds.size() != m_obstacles_for_each_obj.size())
00110         {
00111                 m_gl_obs_clouds.resize(m_obstacles_for_each_obj.size());
00112         }
00113 
00114         // 1st call OR gridmap changed?
00115         if (!m_gui_uptodate)
00116         {
00117                 m_grid.getAs3DObject(m_gl_grid);
00118                 m_gui_uptodate = true;
00119         }
00120 
00121         // Update obstacles:
00122         {
00123                 std::lock_guard<std::mutex> csl(m_gl_obs_clouds_buffer_cs);
00124                 for (size_t i = 0; i < m_gl_obs_clouds.size(); i++)
00125                 {
00126                         mrpt::opengl::CSetOfObjects::Ptr& gl_objs = m_gl_obs_clouds[i];
00127                         if (!gl_objs)
00128                         {
00129                                 gl_objs =
00130                                         mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
00131                                 MRPT_TODO("Add a name, and remove old ones in scene, etc.")
00132                                 SCENE_INSERT_Z_ORDER(scene, 1, gl_objs);
00133                         }
00134 
00135                         // Now that we are in a safe thread (with the OpenGL scene lock
00136                         // adquired from the caller)
00137                         // proceed to replace the old with the new point cloud:
00138                         gl_objs->clear();
00139                         if (m_gl_obs_clouds_buffer.size() > i)
00140                                 gl_objs->insert(m_gl_obs_clouds_buffer[i]);
00141                 }
00142 
00143                 m_gl_obs_clouds_buffer.clear();
00144         }  // end lock
00145 }
00146 
00147 void OccupancyGridMap::simul_pre_timestep(const TSimulContext& context)
00148 {
00149         // Make a list of objects subject to collide with the occupancy grid:
00150         // - Vehicles
00151         // - Blocks
00152         {
00153                 const World::TListVehicles& lstVehs =
00154                         this->m_world->getListOfVehicles();
00155                 const World::TListBlocks& lstBlocks = this->m_world->getListOfBlocks();
00156                 const size_t nObjs = lstVehs.size() + lstBlocks.size();
00157 
00158                 m_obstacles_for_each_obj.resize(nObjs);
00159                 size_t obj_idx = 0;
00160                 for (World::TListVehicles::const_iterator itVeh = lstVehs.begin();
00161                          itVeh != lstVehs.end(); ++itVeh, ++obj_idx)
00162                 {
00163                         TInfoPerCollidableobj& ipv = m_obstacles_for_each_obj[obj_idx];
00164                         ipv.max_obstacles_ranges =
00165                                 itVeh->second->getMaxVehicleRadius() * 1.50f;
00166                         const mrpt::math::TPose3D& pose = itVeh->second->getPose();
00167                         ipv.pose = mrpt::poses::CPose2D(
00168                                 pose.x, pose.y,
00169                                 0 /* angle=0, no need to rotate everything to later rotate back again! */);
00170                 }
00171                 for (World::TListBlocks::const_iterator it = lstBlocks.begin();
00172                          it != lstBlocks.end(); ++it, ++obj_idx)
00173                 {
00174                         TInfoPerCollidableobj& ipv = m_obstacles_for_each_obj[obj_idx];
00175                         ipv.max_obstacles_ranges = it->second->getMaxBlockRadius() * 1.50f;
00176                         const mrpt::math::TPose3D& pose = it->second->getPose();
00177                         ipv.pose = mrpt::poses::CPose2D(
00178                                 pose.x, pose.y,
00179                                 0 /* angle=0, no need to rotate everything to later rotate back again! */);
00180                 }
00181         }
00182 
00183         // For each object, create a ground body with fixtures at each scanned point
00184         // around the vehicle, so it can collide with the environment:
00185         // Upon first usage, reserve mem:
00186         {  // lock
00187                 std::lock_guard<std::mutex> csl(m_gl_obs_clouds_buffer_cs);
00188                 const size_t nObjs = m_obstacles_for_each_obj.size();
00189                 m_gl_obs_clouds_buffer.resize(nObjs);
00190 
00191                 for (size_t obj_idx = 0; obj_idx < nObjs; obj_idx++)
00192                 {
00193                         // 1) Simulate scan to get obstacles around the vehicle:
00194                         TInfoPerCollidableobj& ipv = m_obstacles_for_each_obj[obj_idx];
00195                         CObservation2DRangeScan::Ptr& scan = ipv.scan;
00196                         // Upon first time, reserve mem:
00197                         if (!scan)
00198                                 scan = mrpt::make_aligned_shared<CObservation2DRangeScan>();
00199 
00200                         const float veh_max_obstacles_ranges = ipv.max_obstacles_ranges;
00201                         const float occup_threshold = 0.5f;
00202                         const size_t nRays = 50;
00203 
00204                         scan->aperture = 2.0 * M_PI;  // 360 field of view
00205                         scan->maxRange = veh_max_obstacles_ranges;
00206 
00207                         m_grid.laserScanSimulator(
00208                                 *scan, ipv.pose, occup_threshold, nRays, 0.0f /*noise*/);
00209 
00210                         // Since we'll dilate obstacle points, let's give a bit more space
00211                         // as compensation:
00212                         const float range_enlarge = 0.25f * m_grid.getResolution();
00213                         for (size_t k = 0; k < scan->scan.size(); k++)
00214                         {
00215 #if MRPT_VERSION >= 0x150
00216                                 scan->setScanRange(k, scan->getScanRange(k) + range_enlarge);
00217 #else
00218                                 scan->scan[k] += range_enlarge;
00219 #endif
00220                         }
00221                         // 2) Create a Box2D "ground body" with square "fixtures" so the
00222                         // vehicle can collide with the occ. grid:
00223                         b2World* b2world = m_world->getBox2DWorld();
00224 
00225                         // Create Box2D objects upon first usage:
00226                         if (!ipv.collide_body)
00227                         {
00228                                 b2BodyDef bdef;
00229                                 ipv.collide_body = b2world->CreateBody(&bdef);
00230                                 ASSERT_(ipv.collide_body)
00231                         }
00232                         // Force move the body to the vehicle origins (to use obstacles in
00233                         // local coords):
00234                         ipv.collide_body->SetTransform(
00235                                 b2Vec2(ipv.pose.x(), ipv.pose.y()), .0f);
00236 
00237                         // GL:
00238                         // 1st usage?
00239                         mrpt::opengl::CPointCloud::Ptr& gl_pts =
00240                                 m_gl_obs_clouds_buffer[obj_idx];
00241                         if (m_show_grid_collision_points)
00242                         {
00243                                 gl_pts = mrpt::make_aligned_shared<mrpt::opengl::CPointCloud>();
00244                                 gl_pts->setPointSize(4.0f);
00245                                 gl_pts->setColor(0, 0, 1);
00246 
00247                                 gl_pts->setVisibility(m_show_grid_collision_points);
00248                                 gl_pts->setPose(mrpt::poses::CPose2D(ipv.pose));
00249                                 gl_pts->clear();
00250                         }
00251 
00252                         // Physical properties of each "occupied cell":
00253                         const float occCellSemiWidth = m_grid.getResolution() * 0.4f;
00254                         b2PolygonShape sqrPoly;
00255                         sqrPoly.SetAsBox(occCellSemiWidth, occCellSemiWidth);
00256                         sqrPoly.m_radius = 1e-3;  // The "skin" depth of the body
00257                         b2FixtureDef fixtureDef;
00258                         fixtureDef.shape = &sqrPoly;
00259                         fixtureDef.restitution = m_restitution;
00260                         fixtureDef.density = 0;  // Fixed (inf. mass)
00261                         fixtureDef.friction = m_lateral_friction;  // 0.5f;
00262 
00263                         // Create fixtures at their place (or disable it if no obstacle has
00264                         // been sensed):
00265                         const CSinCosLookUpTableFor2DScans::TSinCosValues& sincos_tab =
00266                                 m_sincos_lut.getSinCosForScan(*scan);
00267                         ipv.collide_fixtures.resize(nRays);
00268                         for (size_t k = 0; k < nRays; k++)
00269                         {
00270                                 if (!ipv.collide_fixtures[k].fixture)
00271                                         ipv.collide_fixtures[k].fixture =
00272                                                 ipv.collide_body->CreateFixture(&fixtureDef);
00273 
00274                                 if (!scan->validRange[k])
00275                                 {
00276                                         ipv.collide_fixtures[k].fixture->SetSensor(
00277                                                 true);  // Box2D's way of saying: don't collide with
00278                                                                 // this!
00279                                         ipv.collide_fixtures[k].fixture->SetUserData(
00280                                                 INVISIBLE_FIXTURE_USER_DATA);
00281                                 }
00282                                 else
00283                                 {
00284                                         ipv.collide_fixtures[k].fixture->SetSensor(
00285                                                 false);  // Box2D's way of saying: don't collide with
00286                                                                  // this!
00287                                         ipv.collide_fixtures[k].fixture->SetUserData(NULL);
00288 
00289                                         b2PolygonShape* poly = dynamic_cast<b2PolygonShape*>(
00290                                                 ipv.collide_fixtures[k].fixture->GetShape());
00291                                         ASSERT_(poly != NULL)
00292 
00293                                         const float llx = sincos_tab.ccos[k] * scan->scan[k];
00294                                         const float lly = sincos_tab.csin[k] * scan->scan[k];
00295 
00296                                         const float ggx = ipv.pose.x() + llx;
00297                                         const float ggy = ipv.pose.y() + lly;
00298 
00299                                         const float gx = m_grid.idx2x(m_grid.x2idx(ggx));
00300                                         const float gy = m_grid.idx2y(m_grid.y2idx(ggy));
00301 
00302                                         const float lx = gx - ipv.pose.x();
00303                                         const float ly = gy - ipv.pose.y();
00304 
00305                                         poly->SetAsBox(
00306                                                 occCellSemiWidth, occCellSemiWidth, b2Vec2(lx, ly),
00307                                                 .0f /*angle*/);
00308 
00309                                         if (gl_pts && m_show_grid_collision_points)
00310                                         {
00311                                                 gl_pts->mrpt::opengl::CPointCloud::insertPoint(
00312                                                         lx, ly, .0);
00313                                         }
00314                                 }
00315                         }
00316                 }  // end for obj_idx
00317 
00318         }  // end lock
00319 }


mvsim
Author(s):
autogenerated on Thu Sep 7 2017 09:27:48