00001
00002
00003
00004
00005
00006
00007
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 <rapidxml.hpp>
00019
00020 #include <mrpt/version.h>
00021 #if MRPT_VERSION >= 0x130
00022 #include <mrpt/maps/CSimplePointsMap.h>
00023 using mrpt::maps::CSimplePointsMap;
00024 #else
00025 #include <mrpt/slam/CSimplePointsMap.h>
00026 using mrpt::slam::CSimplePointsMap;
00027 #endif
00028
00029 #if MRPT_VERSION >= 0x199
00030 #include <mrpt/serialization/CArchive.h>
00031 #endif
00032
00033
00034 using namespace rapidxml;
00035 using namespace mvsim;
00036 using namespace std;
00037
00038 OccupancyGridMap::OccupancyGridMap(
00039 World* parent, const rapidxml::xml_node<char>* root)
00040 : WorldElementBase(parent),
00041 m_gui_uptodate(false),
00042 m_show_grid_collision_points(true),
00043 m_restitution(0.01),
00044 m_lateral_friction(0.5)
00045 {
00046 loadConfigFrom(root);
00047 }
00048
00049 OccupancyGridMap::~OccupancyGridMap() {}
00050 void OccupancyGridMap::loadConfigFrom(const rapidxml::xml_node<char>* root)
00051 {
00052 m_gui_uptodate = false;
00053
00054
00055 xml_node<>* xml_file = root->first_node("file");
00056 if (!xml_file || !xml_file->value())
00057 throw std::runtime_error(
00058 "Error: <file></file> XML entry not found inside gridmap node!");
00059
00060 const string sFile = m_world->resolvePath(xml_file->value());
00061 const string sFileExt =
00062 mrpt::system::extractFileExtension(sFile, true );
00063
00064
00065 if (sFileExt == "gridmap")
00066 {
00067 mrpt::utils::CFileGZInputStream fi(sFile);
00068 #if MRPT_VERSION>=0x199
00069 auto f = mrpt::serialization::archiveFrom(fi);
00070 #else
00071 auto &f = fi;
00072 #endif
00073 f >> m_grid;
00074 }
00075 else
00076
00077 {
00078 std::map<std::string, TParamEntry> other_params;
00079 double xcenterpixel = -1, ycenterpixel = -1;
00080 double resolution = 0.10;
00081
00082 other_params["resolution"] = TParamEntry("%lf", &resolution);
00083 other_params["centerpixel_x"] = TParamEntry("%lf", &xcenterpixel);
00084 other_params["centerpixel_y"] = TParamEntry("%lf", &ycenterpixel);
00085
00086 parse_xmlnode_children_as_param(*root, other_params);
00087
00088 if (!m_grid.loadFromBitmapFile(
00089 sFile, resolution,
00090 #if MRPT_VERSION>=0x199
00091 {xcenterpixel, ycenterpixel}
00092 #else
00093 xcenterpixel, ycenterpixel
00094 #endif
00095 ))
00096 throw std::runtime_error(
00097 mrpt::format(
00098 "[OccupancyGridMap] ERROR: File not found '%s'",
00099 sFile.c_str()));
00100 }
00101
00102 {
00103
00104 std::map<std::string, TParamEntry> ps;
00105 ps["show_collisions"] =
00106 TParamEntry("%bool", &m_show_grid_collision_points);
00107 ps["restitution"] = TParamEntry("%lf", &m_restitution);
00108 ps["lateral_friction"] = TParamEntry("%lf", &m_lateral_friction);
00109
00110 parse_xmlnode_children_as_param(*root, ps);
00111 }
00112 }
00113
00114 void OccupancyGridMap::gui_update(mrpt::opengl::COpenGLScene& scene)
00115 {
00116 using namespace mrpt::math;
00117
00118
00119 if (!m_gl_grid)
00120 {
00121 m_gl_grid = mrpt::opengl::CSetOfObjects::Create();
00122 SCENE_INSERT_Z_ORDER(scene, 0, m_gl_grid);
00123 }
00124 if (m_gl_obs_clouds.size() != m_obstacles_for_each_obj.size())
00125 {
00126 m_gl_obs_clouds.resize(m_obstacles_for_each_obj.size());
00127 }
00128
00129
00130 if (!m_gui_uptodate)
00131 {
00132 m_grid.getAs3DObject(m_gl_grid);
00133 m_gui_uptodate = true;
00134 }
00135
00136
00137 {
00138 std::lock_guard<std::mutex> csl(m_gl_obs_clouds_buffer_cs);
00139 for (size_t i = 0; i < m_gl_obs_clouds.size(); i++)
00140 {
00141 mrpt::opengl::CSetOfObjects::Ptr& gl_objs = m_gl_obs_clouds[i];
00142 if (!gl_objs)
00143 {
00144 gl_objs = mrpt::opengl::CSetOfObjects::Create();
00145 MRPT_TODO("Add a name, and remove old ones in scene, etc.")
00146 SCENE_INSERT_Z_ORDER(scene, 1, gl_objs);
00147 }
00148
00149
00150
00151
00152 gl_objs->clear();
00153 if (m_gl_obs_clouds_buffer.size() > i)
00154 gl_objs->insert(m_gl_obs_clouds_buffer[i]);
00155 }
00156
00157 m_gl_obs_clouds_buffer.clear();
00158 }
00159 }
00160
00161 void OccupancyGridMap::simul_pre_timestep(const TSimulContext& context)
00162 {
00163
00164
00165
00166 {
00167 const World::TListVehicles& lstVehs =
00168 this->m_world->getListOfVehicles();
00169 const World::TListBlocks& lstBlocks = this->m_world->getListOfBlocks();
00170 const size_t nObjs = lstVehs.size() + lstBlocks.size();
00171
00172 m_obstacles_for_each_obj.resize(nObjs);
00173 size_t obj_idx = 0;
00174 for (World::TListVehicles::const_iterator itVeh = lstVehs.begin();
00175 itVeh != lstVehs.end(); ++itVeh, ++obj_idx)
00176 {
00177 TInfoPerCollidableobj& ipv = m_obstacles_for_each_obj[obj_idx];
00178 ipv.max_obstacles_ranges =
00179 itVeh->second->getMaxVehicleRadius() * 1.50f;
00180 const mrpt::math::TPose3D& pose = itVeh->second->getPose();
00181 ipv.pose = mrpt::poses::CPose2D(
00182 pose.x, pose.y,
00183 0 );
00184 }
00185 for (World::TListBlocks::const_iterator it = lstBlocks.begin();
00186 it != lstBlocks.end(); ++it, ++obj_idx)
00187 {
00188 TInfoPerCollidableobj& ipv = m_obstacles_for_each_obj[obj_idx];
00189 ipv.max_obstacles_ranges = it->second->getMaxBlockRadius() * 1.50f;
00190 const mrpt::math::TPose3D& pose = it->second->getPose();
00191 ipv.pose = mrpt::poses::CPose2D(
00192 pose.x, pose.y,
00193 0 );
00194 }
00195 }
00196
00197
00198
00199
00200 {
00201 std::lock_guard<std::mutex> csl(m_gl_obs_clouds_buffer_cs);
00202 const size_t nObjs = m_obstacles_for_each_obj.size();
00203 m_gl_obs_clouds_buffer.resize(nObjs);
00204
00205 for (size_t obj_idx = 0; obj_idx < nObjs; obj_idx++)
00206 {
00207
00208 TInfoPerCollidableobj& ipv = m_obstacles_for_each_obj[obj_idx];
00209 CObservation2DRangeScan::Ptr& scan = ipv.scan;
00210
00211 if (!scan)
00212 scan = CObservation2DRangeScan::Create();
00213
00214 const float veh_max_obstacles_ranges = ipv.max_obstacles_ranges;
00215 const float occup_threshold = 0.5f;
00216 const size_t nRays = 50;
00217
00218 scan->aperture = 2.0 * M_PI;
00219 scan->maxRange = veh_max_obstacles_ranges;
00220
00221 m_grid.laserScanSimulator(
00222 *scan, ipv.pose, occup_threshold, nRays, 0.0f );
00223
00224
00225
00226 const float range_enlarge = 0.25f * m_grid.getResolution();
00227 for (size_t k = 0; k < scan->scan.size(); k++)
00228 {
00229 #if MRPT_VERSION >= 0x150
00230 scan->setScanRange(k, scan->getScanRange(k) + range_enlarge);
00231 #else
00232 scan->scan[k] += range_enlarge;
00233 #endif
00234 }
00235
00236
00237 b2World* b2world = m_world->getBox2DWorld();
00238
00239
00240 if (!ipv.collide_body)
00241 {
00242 b2BodyDef bdef;
00243 ipv.collide_body = b2world->CreateBody(&bdef);
00244 ASSERT_(ipv.collide_body);
00245 }
00246
00247
00248 ipv.collide_body->SetTransform(
00249 b2Vec2(ipv.pose.x(), ipv.pose.y()), .0f);
00250
00251
00252
00253 mrpt::opengl::CPointCloud::Ptr& gl_pts =
00254 m_gl_obs_clouds_buffer[obj_idx];
00255 if (m_show_grid_collision_points)
00256 {
00257 gl_pts = mrpt::opengl::CPointCloud::Create();
00258 gl_pts->setPointSize(4.0f);
00259 gl_pts->setColor(0, 0, 1);
00260
00261 gl_pts->setVisibility(m_show_grid_collision_points);
00262 gl_pts->setPose(mrpt::poses::CPose2D(ipv.pose));
00263 gl_pts->clear();
00264 }
00265
00266
00267 const float occCellSemiWidth = m_grid.getResolution() * 0.4f;
00268 b2PolygonShape sqrPoly;
00269 sqrPoly.SetAsBox(occCellSemiWidth, occCellSemiWidth);
00270 sqrPoly.m_radius = 1e-3;
00271 b2FixtureDef fixtureDef;
00272 fixtureDef.shape = &sqrPoly;
00273 fixtureDef.restitution = m_restitution;
00274 fixtureDef.density = 0;
00275 fixtureDef.friction = m_lateral_friction;
00276
00277
00278
00279 const CSinCosLookUpTableFor2DScans::TSinCosValues& sincos_tab =
00280 m_sincos_lut.getSinCosForScan(*scan);
00281 ipv.collide_fixtures.resize(nRays);
00282 for (size_t k = 0; k < nRays; k++)
00283 {
00284 if (!ipv.collide_fixtures[k].fixture)
00285 ipv.collide_fixtures[k].fixture =
00286 ipv.collide_body->CreateFixture(&fixtureDef);
00287
00288 if (!scan->validRange[k])
00289 {
00290 ipv.collide_fixtures[k].fixture->SetSensor(
00291 true);
00292
00293 ipv.collide_fixtures[k].fixture->SetUserData(
00294 INVISIBLE_FIXTURE_USER_DATA);
00295 }
00296 else
00297 {
00298 ipv.collide_fixtures[k].fixture->SetSensor(
00299 false);
00300
00301 ipv.collide_fixtures[k].fixture->SetUserData(NULL);
00302
00303 b2PolygonShape* poly = dynamic_cast<b2PolygonShape*>(
00304 ipv.collide_fixtures[k].fixture->GetShape());
00305 ASSERT_(poly != NULL);
00306
00307 const float llx = sincos_tab.ccos[k] * scan->scan[k];
00308 const float lly = sincos_tab.csin[k] * scan->scan[k];
00309
00310 const float ggx = ipv.pose.x() + llx;
00311 const float ggy = ipv.pose.y() + lly;
00312
00313 const float gx = m_grid.idx2x(m_grid.x2idx(ggx));
00314 const float gy = m_grid.idx2y(m_grid.y2idx(ggy));
00315
00316 const float lx = gx - ipv.pose.x();
00317 const float ly = gy - ipv.pose.y();
00318
00319 poly->SetAsBox(
00320 occCellSemiWidth, occCellSemiWidth, b2Vec2(lx, ly),
00321 .0f );
00322
00323 if (gl_pts && m_show_grid_collision_points)
00324 {
00325 gl_pts->mrpt::opengl::CPointCloud::insertPoint(
00326 lx, ly, .0);
00327 }
00328 }
00329 }
00330 }
00331
00332 }
00333 }