12 #include <octomap/octomap.h>
13 #include <octomap/OcTree.h>
39 void COctoMap::TMapDefinition::loadFromConfigFile_map_specific(
45 sectionNamePrefix +
string(
"_creationOpts");
48 insertionOpts.loadFromConfigFile(
49 source, sectionNamePrefix +
string(
"_insertOpts"));
50 likelihoodOpts.loadFromConfigFile(
51 source, sectionNamePrefix +
string(
"_likelihoodOpts"));
54 void COctoMap::TMapDefinition::dumpToTextStream_map_specific(
55 std::ostream& out)
const
59 this->insertionOpts.dumpToTextStream(out);
60 this->likelihoodOpts.dumpToTextStream(out);
85 COctoMap::~COctoMap() {}
86 uint8_t COctoMap::serializeGetVersion()
const {
return 3; }
89 this->likelihoodOptions.writeToStream(out);
90 this->renderingOptions.writeToStream(out);
91 out << genericMapParams;
94 const_cast<octomap::OcTree*
>(&m_impl->m_octomap)
109 "Deserialization of old versions of this class was "
110 "discontinued in MRPT 1.9.9 [no CMemoryChunk]");
115 this->likelihoodOptions.readFromStream(
in);
116 if (version >= 1) this->renderingOptions.readFromStream(
in);
117 if (version >= 2)
in >> genericMapParams;
126 std::stringstream ss;
129 m_impl->m_octomap.readBinary(ss);
138 bool COctoMap::internal_insertObservation(
141 octomap::point3d sensorPt;
142 octomap::Pointcloud scan;
143 if (!internal_build_PointCloud_for_observation(
144 obs, robotPose, sensorPt, scan))
149 scan, sensorPt, insertionOptions.maxrange,
150 insertionOptions.pruning);
160 octomap::OcTree::tree_iterator it_end =
161 m_impl->m_octomap.end_tree();
163 const unsigned char max_depth = 0;
165 const TColor general_color_u(
166 general_color.
R * 255, general_color.
G * 255, general_color.
B * 255,
167 general_color.
A * 255);
178 const size_t nLeafs = this->getNumLeafNodes();
182 double xmin, xmax, ymin, ymax, zmin,
zmax, inv_dz;
183 this->getMetricMin(xmin, ymin, zmin);
184 this->getMetricMax(xmax, ymax,
zmax);
185 inv_dz = 1 / (
zmax - zmin + 0.01);
187 for (octomap::OcTree::tree_iterator it =
188 m_impl->m_octomap.begin_tree(max_depth);
191 const octomap::point3d vx_center = it.getCoordinate();
192 const double vx_length = it.getSize();
193 const double L = 0.5 * vx_length;
198 const double occ = it->getOccupancy();
199 if ((occ >= 0.5 && renderingOptions.generateOccupiedVoxels) ||
200 (occ < 0.5 && renderingOptions.generateFreeVoxels))
206 case COctoMapVoxels::FIXED:
207 vx_color = general_color_u;
209 case COctoMapVoxels::COLOR_FROM_HEIGHT:
210 coefc = 255 * inv_dz * (vx_center.z() - zmin);
212 coefc * general_color.
R, coefc * general_color.
G,
213 coefc * general_color.
B, 255.0 * general_color.
A);
216 case COctoMapVoxels::COLOR_FROM_OCCUPANCY:
217 coefc = 240 * (1 - occ) + 15;
219 coefc * general_color.
R, coefc * general_color.
G,
220 coefc * general_color.
B, 255.0 * general_color.
A);
223 case COctoMapVoxels::TRANSPARENCY_FROM_OCCUPANCY:
224 coeft = 255 - 510 * (1 - occ);
230 255 * general_color.
R, 255 * general_color.
G,
231 255 * general_color.
B, coeft);
234 case COctoMapVoxels::TRANS_AND_COLOR_FROM_OCCUPANCY:
235 coefc = 240 * (1 - occ) + 15;
237 coefc * general_color.
R, coefc * general_color.
G,
238 coefc * general_color.
B, 50);
241 case COctoMapVoxels::MIXED:
242 coefc = 255 * inv_dz * (vx_center.z() - zmin);
243 coeft = 255 - 510 * (1 - occ);
249 coefc * general_color.
R, coefc * general_color.
G,
250 coefc * general_color.
B, coeft);
257 const size_t vx_set =
258 (m_impl->m_octomap.isNodeOccupied(*it))
265 TPoint3D(vx_center.x(), vx_center.y(), vx_center.z()),
266 vx_length, vx_color));
269 else if (renderingOptions.generateGridLines)
273 vx_center.x() - L, vx_center.y() - L, vx_center.z() - L);
275 vx_center.x() + L, vx_center.y() + L, vx_center.z() + L);
288 this->getMetricMin(bbmin.
x, bbmin.
y, bbmin.
z);
289 this->getMetricMax(bbmax.
x, bbmax.
y, bbmax.
z);
294 void COctoMap::insertRay(
295 const float end_x,
const float end_y,
const float end_z,
296 const float sensor_x,
const float sensor_y,
const float sensor_z)
300 octomap::point3d(sensor_x, sensor_y, sensor_z),
301 octomap::point3d(end_x, end_y, end_z), insertionOptions.maxrange,
302 insertionOptions.pruning);
304 void COctoMap::updateVoxel(
305 const double x,
const double y,
const double z,
bool occupied)
307 m_impl->m_octomap.updateNode(
x,
y,
z, occupied);
309 bool COctoMap::isPointWithinOctoMap(
310 const float x,
const float y,
const float z)
const
312 octomap::OcTreeKey key;
313 return m_impl->m_octomap
314 .coordToKeyChecked(octomap::point3d(
x,
y,
z), key);
317 double COctoMap::getResolution()
const
319 return m_impl->m_octomap.getResolution();
321 unsigned int COctoMap::getTreeDepth()
const
323 return m_impl->m_octomap.getTreeDepth();
327 return m_impl->m_octomap.size();
329 size_t COctoMap::memoryUsage()
const
331 return m_impl->m_octomap.memoryUsage();
333 size_t COctoMap::memoryUsageNode()
const
335 return m_impl->m_octomap.memoryUsageNode();
337 size_t COctoMap::memoryFullGrid()
const
339 return m_impl->m_octomap.memoryFullGrid();
341 double COctoMap::volume() {
return m_impl->m_octomap.volume(); }
342 void COctoMap::getMetricSize(
double&
x,
double&
y,
double&
z)
344 return m_impl->m_octomap.getMetricSize(
x,
y,
z);
346 void COctoMap::getMetricSize(
double&
x,
double&
y,
double&
z)
const
348 return m_impl->m_octomap.getMetricSize(
x,
y,
z);
350 void COctoMap::getMetricMin(
double&
x,
double&
y,
double&
z)
352 return m_impl->m_octomap.getMetricMin(
x,
y,
z);
354 void COctoMap::getMetricMin(
double&
x,
double&
y,
double&
z)
const
356 return m_impl->m_octomap.getMetricMin(
x,
y,
z);
358 void COctoMap::getMetricMax(
double&
x,
double&
y,
double&
z)
360 return m_impl->m_octomap.getMetricMax(
x,
y,
z);
362 void COctoMap::getMetricMax(
double&
x,
double&
y,
double&
z)
const
364 return m_impl->m_octomap.getMetricMax(
x,
y,
z);
366 size_t COctoMap::calcNumNodes()
const
368 return m_impl->m_octomap.calcNumNodes();
370 size_t COctoMap::getNumLeafNodes()
const
372 return m_impl->m_octomap.getNumLeafNodes();
374 void COctoMap::setOccupancyThres(
double prob)
376 m_impl->m_octomap.setOccupancyThres(prob);
378 void COctoMap::setProbHit(
double prob)
380 m_impl->m_octomap.setProbHit(prob);
382 void COctoMap::setProbMiss(
double prob)
384 m_impl->m_octomap.setProbMiss(prob);
386 void COctoMap::setClampingThresMin(
double thresProb)
388 m_impl->m_octomap.setClampingThresMin(thresProb);
390 void COctoMap::setClampingThresMax(
double thresProb)
392 m_impl->m_octomap.setClampingThresMax(thresProb);
394 double COctoMap::getOccupancyThres()
const
396 return m_impl->m_octomap.getOccupancyThres();
398 float COctoMap::getOccupancyThresLog()
const
400 return m_impl->m_octomap.getOccupancyThresLog();
402 double COctoMap::getProbHit()
const
404 return m_impl->m_octomap.getProbHit();
406 float COctoMap::getProbHitLog()
const
408 return m_impl->m_octomap.getProbHitLog();
410 double COctoMap::getProbMiss()
const
412 return m_impl->m_octomap.getProbMiss();
414 float COctoMap::getProbMissLog()
const
416 return m_impl->m_octomap.getProbMissLog();
418 double COctoMap::getClampingThresMin()
const
420 return m_impl->m_octomap.getClampingThresMin();
422 float COctoMap::getClampingThresMinLog()
const
424 return m_impl->m_octomap.getClampingThresMinLog();
426 double COctoMap::getClampingThresMax()
const
428 return m_impl->m_octomap.getClampingThresMax();
430 float COctoMap::getClampingThresMaxLog()
const
432 return m_impl->m_octomap.getClampingThresMaxLog();
434 void COctoMap::internal_clear() { m_impl->m_octomap.clear(); }