33 using octomap_msgs::Octomap;
35 bool is_equal (
double a,
double b,
double epsilon = 1.0e-7)
37 return std::abs(a - b) <
epsilon;
44 m_nh_private(private_nh_),
45 m_pointCloudSub(NULL),
46 m_tfPointCloudSub(NULL),
47 m_reconfigureServer(m_config_mutex, private_nh_),
50 m_worldFrameId(
"/map"), m_baseFrameId(
"base_footprint"),
52 m_useColoredMap(false),
54 m_latchedTopics(true),
55 m_publishFreeSpace(false),
59 m_pointcloudMinX(-
std::numeric_limits<double>::
max()),
60 m_pointcloudMaxX(
std::numeric_limits<double>::
max()),
61 m_pointcloudMinY(-
std::numeric_limits<double>::
max()),
62 m_pointcloudMaxY(
std::numeric_limits<double>::
max()),
63 m_pointcloudMinZ(-
std::numeric_limits<double>::
max()),
64 m_pointcloudMaxZ(
std::numeric_limits<double>::
max()),
65 m_occupancyMinZ(-
std::numeric_limits<double>::
max()),
66 m_occupancyMaxZ(
std::numeric_limits<double>::
max()),
67 m_minSizeX(0.0), m_minSizeY(0.0),
68 m_filterSpeckles(false), m_filterGroundPlane(false),
69 m_groundFilterDistance(0.04), m_groundFilterAngle(0.15), m_groundFilterPlaneDistance(0.07),
71 m_incrementalUpdate(false),
74 double probHit, probMiss, thresMin, thresMax;
113 ROS_WARN_STREAM(
"You enabled ground filtering but incoming pointclouds will be pre-filtered in [" 115 <<
"This will not work.");
119 ROS_WARN_STREAM(
"You enabled both height map and RGB color registration. This is contradictory. Defaulting to height map.");
124 #ifdef COLOR_OCTOMAP_SERVER 125 ROS_INFO_STREAM(
"Using RGB color registration (if information available)");
127 ROS_ERROR_STREAM(
"Colored map requested in launch file - node not running/compiled to support colors, please define COLOR_OCTOMAP_SERVER and recompile or launch the octomap_color_server node");
164 ROS_INFO(
"Publishing latched (single publish will take longer, all topics are prepared)");
166 ROS_INFO(
"Publishing non-latched (topics are only prepared as needed, will only be re-published on map change");
184 dynamic_reconfigure::Server<OctomapServerConfig>::CallbackType
f;
209 if (filename.length() <= 3)
212 std::string suffix = filename.substr(filename.length()-3, 3);
217 }
else if (suffix ==
".ot"){
228 ROS_ERROR(
"Could not read OcTree in file, currently there are no other types supported in .ot");
242 double minX, minY, minZ;
243 double maxX, maxY, maxZ;
275 ROS_ERROR_STREAM(
"Transform error of sensor data: " << ex.what() <<
", quitting callback");
279 Eigen::Matrix4f sensorToWorld;
284 pcl::PassThrough<PCLPoint> pass_x;
285 pass_x.setFilterFieldName(
"x");
287 pcl::PassThrough<PCLPoint> pass_y;
288 pass_y.setFilterFieldName(
"y");
290 pcl::PassThrough<PCLPoint> pass_z;
291 pass_z.setFilterFieldName(
"z");
306 ROS_ERROR_STREAM(
"Transform error for ground plane filter: " << ex.what() <<
", quitting callback.\n" 307 "You need to set the base_frame_id or disable filter_ground.");
311 Eigen::Matrix4f sensorToBase, baseToWorld;
316 pcl::transformPointCloud(pc, pc, sensorToBase);
317 pass_x.setInputCloud(pc.makeShared());
319 pass_y.setInputCloud(pc.makeShared());
321 pass_z.setInputCloud(pc.makeShared());
326 pcl::transformPointCloud(pc_ground, pc_ground, baseToWorld);
327 pcl::transformPointCloud(pc_nonground, pc_nonground, baseToWorld);
330 pcl::transformPointCloud(pc, pc, sensorToWorld);
333 pass_x.setInputCloud(pc.makeShared());
335 pass_y.setInputCloud(pc.makeShared());
337 pass_z.setInputCloud(pc.makeShared());
342 pc_ground.header = pc.header;
343 pc_nonground.header = pc.header;
350 ROS_DEBUG(
"Pointcloud insertion in OctomapServer done (%zu+%zu pts (ground/nonground), %f sec)", pc_ground.size(), pc_nonground.size(), total_elapsed);
356 point3d sensorOrigin = pointTfToOctomap(sensorOriginTf);
364 #ifdef COLOR_OCTOMAP_SERVER 365 unsigned char* colors =
new unsigned char[3];
369 KeySet free_cells, occupied_cells;
371 for (PCLPointCloud::const_iterator it = ground.begin(); it != ground.end(); ++it){
372 point3d point(it->x, it->y, it->z);
393 for (PCLPointCloud::const_iterator it = nonground.begin(); it != nonground.end(); ++it){
394 point3d point(it->x, it->y, it->z);
405 occupied_cells.insert(key);
410 #ifdef COLOR_OCTOMAP_SERVER // NB: Only read and interpret color if it's an occupied node 411 m_octree->averageNodeColor(it->x, it->y, it->z, it->r, it->g, it->b);
421 free_cells.insert(endKey);
434 for(KeySet::iterator it = free_cells.begin(), end=free_cells.end(); it!= end; ++it){
435 if (occupied_cells.find(*it) == occupied_cells.end()){
441 for (KeySet::iterator it = occupied_cells.begin(), end=occupied_cells.end(); it!= end; it++) {
472 #ifdef COLOR_OCTOMAP_SERVER 487 if (octomapSize <= 1){
488 ROS_WARN(
"Nothing to publish, octree is empty");
500 visualization_msgs::MarkerArray freeNodesVis;
504 geometry_msgs::Pose pose;
508 visualization_msgs::MarkerArray occupiedNodesVis;
513 pcl::PointCloud<PCLPoint> pclCloud;
530 double z = it.getZ();
531 double half_size = it.getSize() / 2.0;
534 double size = it.getSize();
535 double x = it.getX();
536 double y = it.getY();
537 #ifdef COLOR_OCTOMAP_SERVER 538 int r = it->getColor().r;
539 int g = it->getColor().g;
540 int b = it->getColor().b;
545 ROS_DEBUG(
"Ignoring single speckle at (%f,%f,%f)", x, y, z);
555 if (publishMarkerArray){
556 unsigned idx = it.getDepth();
557 assert(idx < occupiedNodesVis.markers.size());
559 geometry_msgs::Point cubeCenter;
564 occupiedNodesVis.markers[idx].points.push_back(cubeCenter);
566 double minX, minY, minZ, maxX, maxY, maxZ;
571 occupiedNodesVis.markers[idx].colors.push_back(
heightMapColor(h));
574 #ifdef COLOR_OCTOMAP_SERVER 576 std_msgs::ColorRGBA _color; _color.r = (r / 255.); _color.g = (g / 255.); _color.b = (b / 255.); _color.a = 1.0;
577 occupiedNodesVis.markers[idx].colors.push_back(_color);
583 if (publishPointCloud) {
584 #ifdef COLOR_OCTOMAP_SERVER 586 _point.x = x; _point.y = y; _point.z = z;
587 _point.r = r; _point.g = g; _point.b = b;
588 pclCloud.push_back(_point);
590 pclCloud.push_back(
PCLPoint(x, y, z));
596 double z = it.getZ();
597 double half_size = it.getSize() / 2.0;
605 double x = it.getX();
606 double y = it.getY();
609 if (publishFreeMarkerArray){
610 unsigned idx = it.getDepth();
611 assert(idx < freeNodesVis.markers.size());
613 geometry_msgs::Point cubeCenter;
618 freeNodesVis.markers[idx].points.push_back(cubeCenter);
630 if (publishMarkerArray){
631 for (
unsigned i= 0; i < occupiedNodesVis.markers.size(); ++i){
635 occupiedNodesVis.markers[i].header.stamp = rostime;
636 occupiedNodesVis.markers[i].ns =
"map";
637 occupiedNodesVis.markers[i].id = i;
638 occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
639 occupiedNodesVis.markers[i].scale.x = size;
640 occupiedNodesVis.markers[i].scale.y = size;
641 occupiedNodesVis.markers[i].scale.z = size;
643 occupiedNodesVis.markers[i].color =
m_color;
646 if (occupiedNodesVis.markers[i].points.size() > 0)
647 occupiedNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
649 occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
657 if (publishFreeMarkerArray){
658 for (
unsigned i= 0; i < freeNodesVis.markers.size(); ++i){
662 freeNodesVis.markers[i].header.stamp = rostime;
663 freeNodesVis.markers[i].ns =
"map";
664 freeNodesVis.markers[i].id = i;
665 freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
666 freeNodesVis.markers[i].scale.x = size;
667 freeNodesVis.markers[i].scale.y = size;
668 freeNodesVis.markers[i].scale.z = size;
672 if (freeNodesVis.markers[i].points.size() > 0)
673 freeNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
675 freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
683 if (publishPointCloud){
684 sensor_msgs::PointCloud2 cloud;
687 cloud.header.stamp = rostime;
691 if (publishBinaryMap)
699 ROS_DEBUG(
"Map publishing in OctomapServer took %f sec", total_elapsed);
705 OctomapSrv::Response &res)
708 ROS_INFO(
"Sending binary map data on service request");
715 ROS_INFO(
"Binary octomap sent in %f sec", total_elapsed);
720 OctomapSrv::Response &res)
722 ROS_INFO(
"Sending full map data on service request");
734 point3d min = pointMsgToOctomap(req.min);
753 visualization_msgs::MarkerArray occupiedNodesVis;
769 for (
unsigned i= 0; i < occupiedNodesVis.markers.size(); ++i){
772 occupiedNodesVis.markers[i].header.stamp = rostime;
773 occupiedNodesVis.markers[i].ns =
"map";
774 occupiedNodesVis.markers[i].id = i;
775 occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
776 occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
781 visualization_msgs::MarkerArray freeNodesVis;
784 for (
unsigned i= 0; i < freeNodesVis.markers.size(); ++i){
787 freeNodesVis.markers[i].header.stamp = rostime;
788 freeNodesVis.markers[i].ns =
"map";
789 freeNodesVis.markers[i].id = i;
790 freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
791 freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
802 map.header.stamp = rostime;
814 map.header.stamp = rostime;
825 ground.header = pc.header;
826 nonground.header = pc.header;
829 ROS_WARN(
"Pointcloud in OctomapServer too small, skipping ground plane extraction");
833 pcl::ModelCoefficients::Ptr coefficients (
new pcl::ModelCoefficients);
834 pcl::PointIndices::Ptr inliers (
new pcl::PointIndices);
837 pcl::SACSegmentation<PCLPoint> seg;
838 seg.setOptimizeCoefficients (
true);
840 seg.setModelType(pcl::SACMODEL_PERPENDICULAR_PLANE);
841 seg.setMethodType(pcl::SAC_RANSAC);
842 seg.setMaxIterations(200);
844 seg.setAxis(Eigen::Vector3f(0,0,1));
850 pcl::ExtractIndices<PCLPoint> extract;
851 bool groundPlaneFound =
false;
853 while(cloud_filtered.size() > 10 && !groundPlaneFound){
854 seg.setInputCloud(cloud_filtered.makeShared());
855 seg.segment (*inliers, *coefficients);
856 if (inliers->indices.size () == 0){
857 ROS_INFO(
"PCL segmentation did not find any plane.");
862 extract.setInputCloud(cloud_filtered.makeShared());
863 extract.setIndices(inliers);
866 ROS_DEBUG(
"Ground plane found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(),
867 coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3));
868 extract.setNegative (
false);
869 extract.filter (ground);
873 if(inliers->indices.size() != cloud_filtered.size()){
874 extract.setNegative(
true);
876 extract.filter(cloud_out);
877 nonground += cloud_out;
878 cloud_filtered = cloud_out;
881 groundPlaneFound =
true;
883 ROS_DEBUG(
"Horizontal plane (not ground) found: %zu/%zu inliers. Coeff: %f %f %f %f", inliers->indices.size(), cloud_filtered.size(),
884 coefficients->values.at(0), coefficients->values.at(1), coefficients->values.at(2), coefficients->values.at(3));
885 pcl::PointCloud<PCLPoint> cloud_out;
886 extract.setNegative (
false);
887 extract.filter(cloud_out);
888 nonground +=cloud_out;
895 if(inliers->indices.size() != cloud_filtered.size()){
896 extract.setNegative(
true);
897 cloud_out.points.clear();
898 extract.filter(cloud_out);
899 cloud_filtered = cloud_out;
901 cloud_filtered.points.clear();
907 if (!groundPlaneFound){
908 ROS_WARN(
"No ground plane found in scan");
911 pcl::PassThrough<PCLPoint> second_pass;
912 second_pass.setFilterFieldName(
"z");
914 second_pass.setInputCloud(pc.makeShared());
915 second_pass.filter(ground);
917 second_pass.setFilterLimitsNegative (
true);
918 second_pass.filter(nonground);
938 nav_msgs::MapMetaData oldMapInfo =
m_gridmap.info;
941 double minX, minY, minZ, maxX, maxY, maxZ;
950 ROS_DEBUG(
"MinKey: %d %d %d / MaxKey: %d %d %d", minKey[0], minKey[1], minKey[2], maxKey[0], maxKey[1], maxKey[2]);
955 minX = std::min(minX, -halfPaddedX);
957 minY = std::min(minY, -halfPaddedY);
964 ROS_ERROR(
"Could not create padded min OcTree key at %f %f %f", minPt.
x(), minPt.
y(), minPt.
z());
968 ROS_ERROR(
"Could not create padded max OcTree key at %f %f %f", maxPt.
x(), maxPt.
y(), maxPt.
z());
973 assert(paddedMaxKey[0] >= maxKey[0] && paddedMaxKey[1] >= maxKey[1]);
980 int mapOriginY = minKey[1] - m_paddedMinKey[1];
981 assert(mapOriginX >= 0 && mapOriginY >= 0);
988 m_gridmap.info.origin.position.x = origin.
x() - gridRes*0.5;
989 m_gridmap.info.origin.position.y = origin.
y() - gridRes*0.5;
1002 ROS_DEBUG(
"Rebuilding complete 2D map");
1013 nav_msgs::OccupancyGrid::_data_type::iterator startIt;
1019 assert(mapUpdateBBXMaxX > mapUpdateBBXMinX);
1020 assert(mapUpdateBBXMaxY > mapUpdateBBXMinY);
1022 size_t numCols = mapUpdateBBXMaxX-mapUpdateBBXMinX +1;
1025 uint max_idx =
m_gridmap.info.width*mapUpdateBBXMaxY + mapUpdateBBXMaxX;
1027 ROS_ERROR(
"BBX index not valid: %d (max index %zu for size %d x %d) update-BBX is: [%zu %zu]-[%zu %zu]", max_idx,
m_gridmap.data.size(),
m_gridmap.info.width,
m_gridmap.info.height, mapUpdateBBXMinX, mapUpdateBBXMinY, mapUpdateBBXMaxX, mapUpdateBBXMaxY);
1030 for (
unsigned int j = mapUpdateBBXMinY; j <= mapUpdateBBXMaxY; ++j){
1082 unsigned idx =
mapIdx(it.getKey());
1092 for(
int dx=0; dx < intSize; dx++){
1094 for(
int dy=0; dy < intSize; dy++){
1112 bool neighborFound =
false;
1113 for (key[2] = nKey[2] - 1; !neighborFound && key[2] <= nKey[2] + 1; ++key[2]){
1114 for (key[1] = nKey[1] - 1; !neighborFound && key[1] <= nKey[1] + 1; ++key[1]){
1115 for (key[0] = nKey[0] - 1; !neighborFound && key[0] <= nKey[0] + 1; ++key[0]){
1120 neighborFound =
true;
1127 return neighborFound;
1177 if (
is_equal(config.sensor_model_hit, 1.0))
1178 config.sensor_model_hit -= 1.0e-6;
1180 if (
is_equal(config.sensor_model_miss, 0.0))
1181 config.sensor_model_miss += 1.0e-6;
1189 if (map.info.resolution != oldMapInfo.resolution){
1190 ROS_ERROR(
"Resolution of map changed, cannot be adjusted");
1194 int i_off = int((oldMapInfo.origin.position.x - map.info.origin.position.x)/map.info.resolution +0.5);
1195 int j_off = int((oldMapInfo.origin.position.y - map.info.origin.position.y)/map.info.resolution +0.5);
1197 if (i_off < 0 || j_off < 0
1198 || oldMapInfo.width + i_off > map.info.width
1199 || oldMapInfo.height + j_off > map.info.height)
1201 ROS_ERROR(
"New 2D map does not contain old map area, this case is not implemented");
1205 nav_msgs::OccupancyGrid::_data_type oldMapData = map.data;
1209 map.data.resize(map.info.width * map.info.height, -1);
1211 nav_msgs::OccupancyGrid::_data_type::iterator fromStart, fromEnd, toStart;
1213 for (
int j =0; j < int(oldMapInfo.height); ++j ){
1215 fromStart = oldMapData.begin() + j*oldMapInfo.width;
1216 fromEnd = fromStart + oldMapInfo.width;
1217 toStart = map.data.begin() + ((j+j_off)*
m_gridmap.info.width + i_off);
1218 copy(fromStart, fromEnd, toStart);
1231 std_msgs::ColorRGBA color;
1248 n = v * (1 - s * f);
1253 color.r = v; color.g = n; color.b = m;
1256 color.r = n; color.g = v; color.b = m;
1259 color.r = m; color.g = v; color.b = n;
1262 color.r = m; color.g = n; color.b = v;
1265 color.r = n; color.g = m; color.b = v;
1268 color.r = v; color.g = m; color.b = n;
1271 color.r = 1; color.g = 0.5; color.b = 0.5;
double getClampingThresMin() const
tf::TransformListener m_tfListener
virtual bool octomapBinarySrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res)
iterator begin(unsigned char maxDepth=0) const
void updateInnerOccupancy()
virtual void insertCloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud)
bool m_projectCompleteMap
void publish(const boost::shared_ptr< M > &message) const
virtual bool octomapFullSrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res)
double getProbHit() const
octomap::OcTreeKey m_updateBBXMax
ros::NodeHandle m_nh_private
std::string m_worldFrameId
unsigned short int coordToKey(double coordinate) const
static void updateMaxKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &max)
octomap::OcTreeKey m_updateBBXMin
void setClampingThresMax(double thresProb)
virtual OcTreeNode * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
void setProbHit(double prob)
bool is_equal(double a, double b, double epsilon=1.0e-7)
static bool fullMapToMsg(const OctomapT &octomap, Octomap &msg)
const iterator end() const
double getClampingThresMax() const
void transformAsMatrix(const tf::Transform &bt, Eigen::Matrix4f &out_mat)
virtual void handleFreeNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing free nodes in the updated area (updates 2D map projection here) ...
bool mapChanged(const nav_msgs::MapMetaData &oldMapInfo, const nav_msgs::MapMetaData &newMapInfo)
leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const
OcTreeNode * search(double x, double y, double z, unsigned int depth=0) const
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void publishBinaryOctoMap(const ros::Time &rostime=ros::Time::now()) const
unsigned int getTreeDepth() const
bool isInUpdateBBX(const OcTreeT::iterator &it) const
Test if key is within update area of map (2D, ignores height)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
bool resetSrv(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void reconfigureCallback(octomap_server::OctomapServerConfig &config, uint32_t level)
bool clearBBXSrv(BBXSrv::Request &req, BBXSrv::Response &resp)
static bool binaryMapToMsg(const OctomapT &octomap, Octomap &msg)
ros::ServiceServer m_octomapBinaryService
double keyToCoord(unsigned short int key, unsigned depth) const
static void updateMinKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &min)
std::string m_baseFrameId
bool computeRayKeys(const point3d &origin, const point3d &end, KeyRay &ray) const
TFSIMD_FORCE_INLINE Vector3 normalized() const
static std_msgs::ColorRGBA heightMapColor(double h)
double m_groundFilterPlaneDistance
void setProbMiss(double prob)
virtual void handlePreNodeTraversal(const ros::Time &rostime)
hook that is called before traversing all nodes
octomap::OcTreeKey m_paddedMinKey
virtual void handleOccupiedNode(const OcTreeT::iterator &it)
hook that is called when traversing occupied nodes of the updated Octree
ros::Publisher m_fmarkerPub
bool isSpeckleNode(const octomap::OcTreeKey &key) const
Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution! ...
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std_msgs::ColorRGBA m_color
virtual void getMetricMin(double &x, double &y, double &z)
virtual void insertScan(const tf::Point &sensorOrigin, const PCLPointCloud &ground, const PCLPointCloud &nonground)
update occupancy map with a scan labeled as ground and nonground. The scans should be in the global m...
void adjustMapData(nav_msgs::OccupancyGrid &map, const nav_msgs::MapMetaData &oldMapInfo) const
unsigned m_multires2DScale
unordered_ns::unordered_set< OcTreeKey, OcTreeKey::KeyHash > KeySet
ros::Publisher m_binaryMapPub
TFSIMD_FORCE_INLINE const tfScalar & x() const
void publishFullOctoMap(const ros::Time &rostime=ros::Time::now()) const
std_msgs::ColorRGBA m_colorFree
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
TFSIMD_FORCE_INLINE const tfScalar & z() const
virtual void getMetricMax(double &x, double &y, double &z)
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_tfPointCloudSub
dynamic_reconfigure::Server< OctomapServerConfig > m_reconfigureServer
double getProbMiss() const
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointCloudSub
ros::ServiceServer m_octomapFullService
uint32_t getNumSubscribers() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
double getResolution() const
#define ROS_INFO_STREAM(args)
virtual void handleNode(const OcTreeT::iterator &it)
hook that is called when traversing all nodes of the updated Octree (does nothing here) ...
virtual void publishAll(const ros::Time &rostime=ros::Time::now())
octomath::Vector3 point3d
bool readBinary(std::istream &s)
ros::Publisher m_pointCloudPub
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
virtual void handlePostNodeTraversal(const ros::Time &rostime)
hook that is called after traversing all nodes
double getNodeSize(unsigned depth) const
ros::Publisher m_markerPub
boost::recursive_mutex m_config_mutex
nav_msgs::OccupancyGrid m_gridmap
float logodds(double probability)
virtual void update2DMap(const OcTreeT::iterator &it, bool occupied)
updates the downprojected 2D map as either occupied or free
double m_groundFilterAngle
#define ROS_ERROR_STREAM(args)
ros::ServiceServer m_resetService
unsigned mapIdx(int i, int j) const
ros::Publisher m_fullMapPub
const leaf_bbx_iterator end_leafs_bbx() const
pcl::PointCloud< pcl::PointXYZ > PCLPointCloud
virtual void handleNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing all nodes of the updated Octree in the updated area (does nothing...
bool isNodeOccupied(const OcTreeNode *occupancyNode) const
void filterGroundPlane(const PCLPointCloud &pc, PCLPointCloud &ground, PCLPointCloud &nonground) const
label the input cloud "pc" into ground and nonground. Should be in the robot's fixed frame (not world...
double m_groundFilterDistance
virtual size_t size() const
virtual void handleFreeNode(const OcTreeT::iterator &it)
hook that is called when traversing free nodes of the updated Octree
virtual bool openFile(const std::string &filename)
virtual void handleOccupiedNodeInBBX(const OcTreeT::iterator &it)
hook that is called when traversing occupied nodes in the updated area (updates 2D map projection her...
ros::ServiceServer m_clearBBXService
void setClampingThresMin(double thresProb)
Connection registerCallback(const C &callback)