|
virtual void | handlePostNodeTraversal (const ros::Time &rostime) |
| hook that is called after traversing all nodes More...
|
|
virtual void | handlePreNodeTraversal (const ros::Time &rostime) |
| hook that is called after traversing all nodes More...
|
|
virtual void | update2DMap (const OcTreeT::iterator &it, bool occupied) |
| updates the downprojected 2D map as either occupied or free More...
|
|
void | adjustMapData (nav_msgs::OccupancyGrid &map, const nav_msgs::MapMetaData &oldMapInfo) 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!) More...
|
|
virtual void | handleFreeNode (const OcTreeT::iterator &it) |
| hook that is called when traversing free nodes of the updated Octree More...
|
|
virtual void | handleFreeNodeInBBX (const OcTreeT::iterator &it) |
| hook that is called when traversing free nodes in the updated area (updates 2D map projection here) More...
|
|
virtual void | handleNode (const OcTreeT::iterator &it) |
| hook that is called when traversing all nodes of the updated Octree (does nothing here) More...
|
|
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 here) More...
|
|
virtual void | handleOccupiedNode (const OcTreeT::iterator &it) |
| hook that is called when traversing occupied nodes of the updated Octree More...
|
|
virtual void | handleOccupiedNodeInBBX (const OcTreeT::iterator &it) |
| hook that is called when traversing occupied nodes in the updated area (updates 2D map projection here) More...
|
|
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 map frame. More...
|
|
bool | isInUpdateBBX (const OcTreeT::iterator &it) const |
| Test if key is within update area of map (2D, ignores height) More...
|
|
bool | isSpeckleNode (const octomap::OcTreeKey &key) const |
| Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution! More...
|
|
bool | mapChanged (const nav_msgs::MapMetaData &oldMapInfo, const nav_msgs::MapMetaData &newMapInfo) |
|
unsigned | mapIdx (int i, int j) const |
|
unsigned | mapIdx (const octomap::OcTreeKey &key) const |
|
virtual void | publishAll (const ros::Time &rostime=ros::Time::now()) |
|
void | publishBinaryOctoMap (const ros::Time &rostime=ros::Time::now()) const |
|
void | publishFullOctoMap (const ros::Time &rostime=ros::Time::now()) const |
|
void | reconfigureCallback (octomap_server::OctomapServerConfig &config, uint32_t level) |
|
Definition at line 35 of file OctomapServerMultilayer.h.