10 #include <mrpt/io/CFileGZInputStream.h>
11 #include <mrpt/maps/CSimplePointsMap.h>
12 #include <mrpt/opengl/COpenGLScene.h>
13 #include <mrpt/poses/CPose2D.h>
14 #include <mrpt/serialization/CArchive.h>
15 #include <mrpt/system/filesystem.h>
16 #include <mrpt/version.h>
25 using namespace mvsim;
31 show_grid_collision_points_(true),
33 lateral_friction_(0.5)
46 if (!xml_file || !xml_file->value())
47 throw std::runtime_error(
"Error: <file></file> XML entry not found inside gridmap node!");
50 const string sFileExt = mrpt::system::extractFileExtension(sFile,
true );
53 if (sFileExt ==
"yaml")
55 #if MRPT_VERSION >= 0x250
56 bool ok =
grid_.loadFromROSMapServerYAML(sFile);
57 ASSERTMSG_(
ok, mrpt::format(
"Error loading ROS map file: '%s'", sFile.c_str()));
59 THROW_EXCEPTION(
"Loading ROS YAML map files requires MRPT>=2.5.0");
62 else if (sFileExt ==
"gridmap")
64 mrpt::io::CFileGZInputStream fi(sFile);
65 auto f = mrpt::serialization::archiveFrom(fi);
72 double xcenterpixel = -1, ycenterpixel = -1;
73 double resolution = 0.10;
75 other_params[
"resolution"] =
TParamEntry(
"%lf", &resolution);
76 other_params[
"centerpixel_x"] =
TParamEntry(
"%lf", &xcenterpixel);
77 other_params[
"centerpixel_y"] =
TParamEntry(
"%lf", &ycenterpixel);
81 if (!
grid_.loadFromBitmapFile(sFile, resolution, {xcenterpixel, ycenterpixel}))
82 throw std::runtime_error(
83 mrpt::format(
"[OccupancyGridMap] ERROR: File not found '%s'", sFile.c_str()));
98 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& viz,
99 const mrpt::optional_ref<mrpt::opengl::COpenGLScene>& physical,
100 [[maybe_unused]]
bool childrenOnly)
107 gl_grid_ = mrpt::opengl::CSetOfObjects::Create();
108 gl_grid_->setName(
"OccupancyGridMap");
120 #if MRPT_VERSION >= 0x240
137 gl_objs = mrpt::opengl::CSetOfObjects::Create();
139 "OccupancyGridMap"s + this->
getName() +
".obstacles["s + std::to_string(i) +
141 viz->get().insert(gl_objs);
164 const size_t nObjs = lstVehs.size() + lstBlocks.size();
168 for (World::VehicleList::const_iterator itVeh = lstVehs.begin(); itVeh != lstVehs.end();
173 const mrpt::math::TPose3D& pose = itVeh->second->getPose();
174 ipv.
pose = mrpt::poses::CPose2D(
178 for (
const auto& block : lstBlocks)
182 const mrpt::math::TPose3D& pose = block.second->getPose();
185 ipv.
pose = mrpt::poses::CPose2D(pose.x, pose.y, 0);
199 for (
size_t obj_idx = 0; obj_idx < nObjs; obj_idx++)
203 mrpt::obs::CObservation2DRangeScan::Ptr& scan = ipv.
scan;
205 if (!scan) scan = mrpt::obs::CObservation2DRangeScan::Create();
208 const float occup_threshold = 0.5f;
209 const size_t nRays = 50;
211 scan->aperture = 2.0 * M_PI;
212 scan->maxRange = veh_max_obstacles_ranges;
214 grid_.laserScanSimulator(*scan, ipv.
pose, occup_threshold, nRays, 0.0f );
218 const float range_enlarge = 0.25f *
grid_.getResolution();
219 for (
size_t k = 0; k < scan->getScanSize(); k++)
221 scan->setScanRange(k, scan->getScanRange(k) + range_enlarge);
242 gl_pts = mrpt::opengl::CPointCloud::Create();
243 gl_pts->setPointSize(4.0
f);
244 gl_pts->setColor(0, 0, 1);
247 gl_pts->setPose(mrpt::poses::CPose2D(ipv.
pose));
252 const float occCellSemiWidth =
grid_.getResolution() * 0.4f;
254 sqrPoly.
SetAsBox(occCellSemiWidth, occCellSemiWidth);
257 fixtureDef.
shape = &sqrPoly;
264 const mrpt::obs::CSinCosLookUpTableFor2DScans::TSinCosValues& sincos_tab =
267 for (
size_t k = 0; k < nRays; k++)
272 if (!scan->getScanRangeValidity(k))
286 ASSERT_(poly !=
nullptr);
288 const float llx = sincos_tab.ccos[k] * scan->getScanRange(k);
289 const float lly = sincos_tab.csin[k] * scan->getScanRange(k);
291 const float ggx = ipv.
pose.x() + llx;
292 const float ggy = ipv.
pose.y() + lly;
294 const float gx =
grid_.idx2x(
grid_.x2idx(ggx));
295 const float gy =
grid_.idx2y(
grid_.y2idx(ggy));
297 const float lx = gx - ipv.
pose.x();
298 const float ly = gy - ipv.
pose.y();
301 occCellSemiWidth, occCellSemiWidth,
b2Vec2(lx, ly), .0
f );
305 gl_pts->mrpt::opengl::CPointCloud::insertPoint(lx, ly, .0);