14 #include <mrpt/opengl/COpenGLScene.h> 15 #include <mrpt/poses/CPose2D.h> 16 #include <mrpt/utils/CFileGZInputStream.h> 17 #include <mrpt/system/filesystem.h> 20 #include <mrpt/version.h> 21 #if MRPT_VERSION >= 0x130 22 #include <mrpt/maps/CSimplePointsMap.h> 23 using mrpt::maps::CSimplePointsMap;
25 #include <mrpt/slam/CSimplePointsMap.h> 26 using mrpt::slam::CSimplePointsMap;
29 #if MRPT_VERSION >= 0x199 30 #include <mrpt/serialization/CArchive.h> 35 using namespace mvsim;
38 OccupancyGridMap::OccupancyGridMap(
41 m_gui_uptodate(false),
42 m_show_grid_collision_points(true),
44 m_lateral_friction(0.5)
56 if (!xml_file || !xml_file->
value())
57 throw std::runtime_error(
58 "Error: <file></file> XML entry not found inside gridmap node!");
61 const string sFileExt =
62 mrpt::system::extractFileExtension(sFile,
true );
65 if (sFileExt ==
"gridmap")
67 mrpt::utils::CFileGZInputStream fi(sFile);
68 #if MRPT_VERSION>=0x199 69 auto f = mrpt::serialization::archiveFrom(fi);
78 std::map<std::string, TParamEntry> other_params;
79 double xcenterpixel = -1, ycenterpixel = -1;
80 double resolution = 0.10;
82 other_params[
"resolution"] =
TParamEntry(
"%lf", &resolution);
83 other_params[
"centerpixel_x"] =
TParamEntry(
"%lf", &xcenterpixel);
84 other_params[
"centerpixel_y"] =
TParamEntry(
"%lf", &ycenterpixel);
88 if (!
m_grid.loadFromBitmapFile(
90 #
if MRPT_VERSION>=0x199
91 {xcenterpixel, ycenterpixel}
93 xcenterpixel, ycenterpixel
96 throw std::runtime_error(
98 "[OccupancyGridMap] ERROR: File not found '%s'",
104 std::map<std::string, TParamEntry> ps;
105 ps[
"show_collisions"] =
121 m_gl_grid = mrpt::opengl::CSetOfObjects::Create();
144 gl_objs = mrpt::opengl::CSetOfObjects::Create();
145 MRPT_TODO(
"Add a name, and remove old ones in scene, etc.")
170 const size_t nObjs = lstVehs.size() + lstBlocks.size();
174 for (World::TListVehicles::const_iterator itVeh = lstVehs.begin();
175 itVeh != lstVehs.end(); ++itVeh, ++obj_idx)
179 itVeh->second->getMaxVehicleRadius() * 1.50f;
180 const mrpt::math::TPose3D& pose = itVeh->second->getPose();
181 ipv.
pose = mrpt::poses::CPose2D(
185 for (World::TListBlocks::const_iterator it = lstBlocks.begin();
186 it != lstBlocks.end(); ++it, ++obj_idx)
190 const mrpt::math::TPose3D& pose = it->second->getPose();
191 ipv.
pose = mrpt::poses::CPose2D(
205 for (
size_t obj_idx = 0; obj_idx < nObjs; obj_idx++)
209 CObservation2DRangeScan::Ptr& scan = ipv.
scan;
212 scan = CObservation2DRangeScan::Create();
215 const float occup_threshold = 0.5f;
216 const size_t nRays = 50;
218 scan->aperture = 2.0 * M_PI;
219 scan->maxRange = veh_max_obstacles_ranges;
221 m_grid.laserScanSimulator(
222 *scan, ipv.
pose, occup_threshold, nRays, 0.0f );
226 const float range_enlarge = 0.25f *
m_grid.getResolution();
227 for (
size_t k = 0; k < scan->scan.size(); k++)
229 #if MRPT_VERSION >= 0x150 230 scan->setScanRange(k, scan->getScanRange(k) + range_enlarge);
232 scan->scan[k] += range_enlarge;
253 mrpt::opengl::CPointCloud::Ptr& gl_pts =
257 gl_pts = mrpt::opengl::CPointCloud::Create();
258 gl_pts->setPointSize(4.0
f);
259 gl_pts->setColor(0, 0, 1);
262 gl_pts->setPose(mrpt::poses::CPose2D(ipv.
pose));
267 const float occCellSemiWidth =
m_grid.getResolution() * 0.4f;
269 sqrPoly.
SetAsBox(occCellSemiWidth, occCellSemiWidth);
272 fixtureDef.
shape = &sqrPoly;
279 const CSinCosLookUpTableFor2DScans::TSinCosValues& sincos_tab =
282 for (
size_t k = 0; k < nRays; k++)
288 if (!scan->validRange[k])
305 ASSERT_(poly != NULL);
307 const float llx = sincos_tab.ccos[k] * scan->scan[k];
308 const float lly = sincos_tab.csin[k] * scan->scan[k];
310 const float ggx = ipv.
pose.x() + llx;
311 const float ggy = ipv.
pose.y() + lly;
316 const float lx = gx - ipv.
pose.x();
317 const float ly = gy - ipv.
pose.y();
320 occCellSemiWidth, occCellSemiWidth,
b2Vec2(lx, ly),
325 gl_pts->mrpt::opengl::CPointCloud::insertPoint(
This file contains rapidxml parser and DOM implementation.
const TListBlocks & getListOfBlocks() const
b2Fixture * CreateFixture(const b2FixtureDef *def)
std::vector< mrpt::opengl::CSetOfObjects::Ptr > m_gl_obs_clouds
float max_obstacles_ranges
mrpt::opengl::CSetOfObjects::Ptr m_gl_grid
call of gui_update()
bool m_show_grid_collision_points
std::multimap< std::string, VehicleBase * > TListVehicles
virtual ~OccupancyGridMap()
xml_node< Ch > * first_node(const Ch *name=0, std::size_t name_size=0, bool case_sensitive=true) const
std::vector< TFixturePtr > collide_fixtures
void SetTransform(const b2Vec2 &position, float32 angle)
CSinCosLookUpTableFor2DScans m_sincos_lut
double m_restitution
Elastic restitution coef (default: 0.01)
void parse_xmlnode_children_as_param(const rapidxml::xml_node< char > &xml_node, const std::map< std::string, TParamEntry > ¶ms, const char *function_name_context="")
#define SCENE_INSERT_Z_ORDER(_SCENE, _ZORDER_INDEX, _OBJ_TO_INSERT)
std::string resolvePath(const std::string &in_path) const
virtual void simul_pre_timestep(const TSimulContext &context)
See docs in base class.
std::multimap< std::string, Block * > TListBlocks
virtual void gui_update(mrpt::opengl::COpenGLScene &scene)
See docs in base class.
#define INVISIBLE_FIXTURE_USER_DATA
Used to signal a Box2D fixture as "invisible" to sensors.
float32 density
The density, usually in kg/m^2.
void SetAsBox(float32 hx, float32 hy)
COccupancyGridMap2D m_grid
const TListVehicles & getListOfVehicles() const
std::vector< mrpt::opengl::CPointCloud::Ptr > m_gl_obs_clouds_buffer
float32 restitution
The restitution (elasticity) usually in the range [0,1].
b2World * getBox2DWorld()
double m_lateral_friction
(Default: 0.5)
virtual void loadConfigFrom(const rapidxml::xml_node< char > *root)
See docs in base class.
std::vector< TInfoPerCollidableobj > m_obstacles_for_each_obj
mrpt::poses::CPose2D pose
std::mutex m_gl_obs_clouds_buffer_cs
float32 friction
The friction coefficient, usually in the range [0,1].
CObservation2DRangeScan::Ptr scan
b2Body * CreateBody(const b2BodyDef *def)