LaserScanner.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/World.h>
00011 #include <mvsim/WorldElements/OccupancyGridMap.h>
00012 #include <mvsim/Sensors/LaserScanner.h>
00013 #include <mvsim/VehicleBase.h>
00014 #include <mrpt/opengl/COpenGLScene.h>
00015 #include <mrpt/random.h>
00016 #include <mrpt/version.h>
00017 
00018 #include "xml_utils.h"
00019 
00020 using namespace mvsim;
00021 using namespace rapidxml;
00022 
00023 int z_order_cnt = 0;
00024 
00025 LaserScanner::LaserScanner(
00026         VehicleBase& parent, const rapidxml::xml_node<char>* root)
00027         : SensorBase(parent),
00028           m_z_order(++z_order_cnt),
00029           m_rangeStdNoise(0.01),
00030       m_angleStdNoise(DEG2RAD(0.01)),
00031           m_see_fixtures(true)
00032 {
00033         this->loadConfigFrom(root);
00034 }
00035 
00036 LaserScanner::~LaserScanner() {}
00037 void LaserScanner::loadConfigFrom(const rapidxml::xml_node<char>* root)
00038 {
00039         m_gui_uptodate = false;
00040 
00041         // Attribs:
00042         std::map<std::string, TParamEntry> attribs;
00043         attribs["name"] = TParamEntry("%s", &this->m_name);
00044 
00045         parse_xmlnode_attribs(*root, attribs, "[LaserScanner]");
00046 
00047         // Other scalar params:
00048         int nRays = 181;
00049         double fov_deg = 180;
00050 
00051         std::map<std::string, TParamEntry> params;
00052         params["fov_degrees"] = TParamEntry("%lf", &fov_deg);
00053         params["nrays"] = TParamEntry("%i", &nRays);
00054         params["pose"] = TParamEntry("%pose2d_ptr3d", &m_scan_model.sensorPose);
00055         params["range_std_noise"] = TParamEntry("%lf", &m_rangeStdNoise);
00056         params["angle_std_noise_deg"] = TParamEntry("%lf_deg", &m_angleStdNoise);
00057         params["sensor_period"] = TParamEntry("%lf", &this->m_sensor_period);
00058         params["bodies_visible"] = TParamEntry("%bool", &this->m_see_fixtures);
00059 
00060         // Parse XML params:
00061         parse_xmlnode_children_as_param(*root, params);
00062 
00063         // Pass params to the scan2D obj:
00064         m_scan_model.aperture = DEG2RAD(fov_deg);
00065 #if MRPT_VERSION >= 0x150
00066         m_scan_model.resizeScan(nRays);
00067 #else
00068         m_scan_model.scan.resize(nRays);
00069         m_scan_model.validRange.resize(nRays);
00070 #endif
00071 
00072         // Assign a sensible default name/sensor label if none is provided:
00073         if (m_name.empty())
00074         {
00075                 const size_t nextIdx = m_vehicle.getSensors().size() + 1;
00076                 m_name = mrpt::format("laser%u", static_cast<unsigned int>(nextIdx));
00077         }
00078 }
00079 
00080 void LaserScanner::gui_update(mrpt::opengl::COpenGLScene& scene)
00081 {
00082         // 1st time?
00083         if (!m_gl_scan)
00084         {
00085                 m_gl_scan = mrpt::opengl::CPlanarLaserScan::Create();
00086                 m_gl_scan->setSurfaceColor(0.0f, 0.0f, 1.0f, 0.05f);
00087                 SCENE_INSERT_Z_ORDER(scene, 2, m_gl_scan);
00088         }
00089 
00090         if (!m_gui_uptodate)
00091         {
00092                 {
00093                         std::lock_guard<std::mutex> csl(m_last_scan_cs);
00094                         if (m_last_scan2gui)
00095                         {
00096                                 m_gl_scan->setScan(*m_last_scan2gui);
00097                                 m_last_scan2gui.reset();
00098                         }
00099                 }
00100                 m_gui_uptodate = true;
00101         }
00102 
00103         const double z_incrs = 10e-3;  // for m_z_order
00104         const double z_offset = 10e-2;
00105         const mrpt::poses::CPose2D& p = m_vehicle.getCPose2D();
00106         m_gl_scan->setPose(
00107                 mrpt::poses::CPose3D(
00108                         p.x(), p.y(), z_offset + z_incrs * m_z_order, p.phi(), 0.0, 0.0));
00109 }
00110 
00111 void LaserScanner::simul_pre_timestep(const TSimulContext& context) {}
00112 // Simulate sensor AFTER timestep, with the updated vehicle dynamical state:
00113 void LaserScanner::simul_post_timestep(const TSimulContext& context)
00114 {
00115         // Limit sensor rate:
00116         if (context.simul_time < m_sensor_last_timestamp + m_sensor_period) return;
00117 
00118         m_sensor_last_timestamp = context.simul_time;
00119 
00120         // Create an array of scans, each reflecting ranges to one kind of world
00121         // objects.
00122         // Finally, we'll take the shortest range in each direction:
00123         std::list<CObservation2DRangeScan> lstScans;
00124 
00125         const size_t nRays = m_scan_model.scan.size();
00126         const double maxRange = m_scan_model.maxRange;
00127 
00128         // Get pose of the robot:
00129         const mrpt::poses::CPose2D& vehPose = m_vehicle.getCPose2D();
00130 
00131         // grid maps:
00132         // -------------
00133         m_world->getTimeLogger().enter("LaserScanner.scan.1.gridmap");
00134 
00135         const World::TListWorldElements& elements =
00136                 m_world->getListOfWorldElements();
00137         for (World::TListWorldElements::const_iterator it = elements.begin();
00138                  it != elements.end(); ++it)
00139         {
00140                 // If not a grid map, ignore:
00141                 const OccupancyGridMap* grid =
00142                         dynamic_cast<const OccupancyGridMap*>(*it);
00143                 if (!grid) continue;
00144                 const COccupancyGridMap2D& occGrid = grid->getOccGrid();
00145 
00146                 // Create new scan:
00147                 lstScans.push_back(CObservation2DRangeScan(m_scan_model));
00148                 CObservation2DRangeScan& scan = lstScans.back();
00149 
00150                 // Ray tracing over the gridmap:
00151                 occGrid.laserScanSimulator(
00152                         scan, vehPose, 0.5f, m_scan_model.scan.size(), m_rangeStdNoise, 1,
00153                         m_angleStdNoise);
00154         }
00155         m_world->getTimeLogger().leave("LaserScanner.scan.1.gridmap");
00156 
00157         // ray trace on Box2D polygons:
00158         // ------------------------------
00159         m_world->getTimeLogger().enter("LaserScanner.scan.2.polygons");
00160         {
00161                 // Create new scan:
00162                 lstScans.push_back(CObservation2DRangeScan(m_scan_model));
00163                 CObservation2DRangeScan& scan = lstScans.back();
00164 
00165                 // Do Box2D raycasting stuff:
00166                 // ------------------------------
00167                 // This callback finds the closest hit. Polygon 0 is filtered.
00168                 class RayCastClosestCallback : public b2RayCastCallback
00169                 {
00170                    public:
00171                         RayCastClosestCallback() : m_see_fixtures(true), m_hit(false) {}
00172                         float32 ReportFixture(
00173                                 b2Fixture* fixture, const b2Vec2& point, const b2Vec2& normal,
00174                                 float32 fraction)
00175                         {
00176                                 if (!m_see_fixtures ||
00177                                         fixture->GetUserData() == INVISIBLE_FIXTURE_USER_DATA)
00178                                 {
00179                                         // By returning -1, we instruct the calling code to ignore
00180                                         // this fixture and
00181                                         // continue the ray-cast to the next fixture.
00182                                         return -1.0f;
00183                                 }
00184 
00185                                 m_hit = true;
00186                                 m_point = point;
00187                                 m_normal = normal;
00188                                 // By returning the current fraction, we instruct the calling
00189                                 // code to clip the ray and
00190                                 // continue the ray-cast to the next fixture. WARNING: do not
00191                                 // assume that fixtures
00192                                 // are reported in order. However, by clipping, we can always
00193                                 // get the closest fixture.
00194                                 return fraction;
00195                         }
00196 
00197                         bool m_see_fixtures;
00198                         bool m_hit;
00199                         b2Vec2 m_point;
00200                         b2Vec2 m_normal;
00201                 };
00202 
00203                 const mrpt::poses::CPose2D sensorPose =
00204                         vehPose + mrpt::poses::CPose2D(scan.sensorPose);
00205                 const b2Vec2 sensorPt = b2Vec2(sensorPose.x(), sensorPose.y());
00206 
00207                 RayCastClosestCallback callback;
00208                 callback.m_see_fixtures = m_see_fixtures;
00209 
00210                 // Scan size:
00211                 ASSERT_(nRays >= 2);
00212 #if MRPT_VERSION >= 0x150
00213                 scan.resizeScan(nRays);
00214 #else
00215                 scan.scan.resize(nRays);
00216                 scan.validRange.resize(nRays);
00217 #endif
00218                 double A =
00219                         sensorPose.phi() + (scan.rightToLeft ? -0.5 : +0.5) * scan.aperture;
00220                 const double AA =
00221                         (scan.rightToLeft ? 1.0 : -1.0) * (scan.aperture / (nRays - 1));
00222 
00223                 auto &rnd =
00224 #if MRPT_VERSION >= 0x199
00225                         mrpt::random::getRandomGenerator();
00226 #else
00227                         mrpt::random::randomGenerator;
00228 #endif
00229 
00230                 for (size_t i = 0; i < nRays; i++, A += AA)
00231                 {
00232                         const b2Vec2 endPt = b2Vec2(
00233                                 sensorPt.x + cos(A) * maxRange, sensorPt.y + sin(A) * maxRange);
00234 
00235                         callback.m_hit = false;
00236                         m_world->getBox2DWorld()->RayCast(&callback, sensorPt, endPt);
00237 #if MRPT_VERSION >= 0x150
00238                         scan.setScanRangeValidity(i, callback.m_hit);
00239 #else
00240                         scan.validRange[i] = callback.m_hit ? 1 : 0;
00241 #endif
00242 
00243                         float range = scan.scan[i];
00244                         if (callback.m_hit)
00245                         {
00246                                 // Hit:
00247                                 range = ::hypotf(
00248                                         callback.m_point.x - sensorPt.x,
00249                                         callback.m_point.y - sensorPt.y);
00250                                 range +=
00251                                         rnd.drawGaussian1D_normalized() *
00252                                         m_rangeStdNoise;
00253                         }
00254                         else
00255                         {
00256                                 // Miss:
00257                                 range = maxRange;
00258                         }
00259 #if MRPT_VERSION >= 0x150
00260                         scan.setScanRange(i, range);
00261 #else
00262                         scan.scan[i] = range;
00263 #endif
00264                 }  // end for (raycast scan)
00265         }
00266         m_world->getTimeLogger().leave("LaserScanner.scan.2.polygons");
00267 
00268         // Summarize all scans in one single scan:
00269         // ----------------------------------------
00270         m_world->getTimeLogger().enter("LaserScanner.scan.3.merge");
00271 
00272         CObservation2DRangeScan* lastScan =
00273                 new CObservation2DRangeScan(m_scan_model);
00274         lastScan->timestamp = mrpt::system::now();
00275         lastScan->sensorLabel = m_name;
00276 
00277 #if MRPT_VERSION >= 0x150
00278         lastScan->resizeScanAndAssign(nRays, maxRange, false);
00279 #else
00280         lastScan->scan.assign(nRays, maxRange);
00281         lastScan->validRange.assign(nRays, 0);
00282 #endif
00283 
00284         for (std::list<CObservation2DRangeScan>::const_iterator it =
00285                          lstScans.begin();
00286                  it != lstScans.end(); ++it)
00287         {
00288                 ASSERT_(it->scan.size() == nRays && it->validRange.size() == nRays);
00289 
00290                 for (size_t i = 0; i < nRays; i++)
00291                 {
00292                         if (it->validRange[i])
00293                         {
00294 #if MRPT_VERSION >= 0x150
00295                                 lastScan->setScanRange(
00296                                         i, std::min(lastScan->scan[i], it->scan[i]));
00297                                 lastScan->setScanRangeValidity(i, true);
00298 #else
00299                                 lastScan->scan[i] = std::min(lastScan->scan[i], it->scan[i]);
00300                                 lastScan->validRange[i] = 1;  // valid
00301 #endif
00302                         }
00303                 }
00304         }
00305         m_world->getTimeLogger().leave("LaserScanner.scan.3.merge");
00306 
00307         {
00308                 std::lock_guard<std::mutex> csl(m_last_scan_cs);
00309                 m_last_scan = CObservation2DRangeScan::Ptr(lastScan);
00310                 m_last_scan2gui = m_last_scan;
00311         }
00312 
00313         m_world->onNewObservation(m_vehicle, m_last_scan.get());
00314 
00315         m_gui_uptodate = false;
00316 }


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