#include <OctomapServerMultilayer.h>
Classes | |
struct | ProjectedMap |
Public Member Functions | |
OctomapServerMultilayer (ros::NodeHandle private_nh_=ros::NodeHandle("~")) | |
virtual | ~OctomapServerMultilayer () |
Public Member Functions inherited from octomap_server::OctomapServer | |
bool | clearBBXSrv (BBXSrv::Request &req, BBXSrv::Response &resp) |
virtual void | insertCloudCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud) |
virtual bool | octomapBinarySrv (OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res) |
virtual bool | octomapFullSrv (OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res) |
OctomapServer (const ros::NodeHandle private_nh_=ros::NodeHandle("~"), const ros::NodeHandle &nh_=ros::NodeHandle()) | |
virtual bool | openFile (const std::string &filename) |
bool | resetSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) |
virtual | ~OctomapServer () |
Protected Types | |
typedef std::vector< ProjectedMap > | MultilevelGrid |
Protected Member Functions | |
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... | |
Protected Member Functions inherited from octomap_server::OctomapServer | |
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 | publishProjected2DMap (const ros::Time &rostime=ros::Time::now()) |
void | reconfigureCallback (octomap_server::OctomapServerConfig &config, uint32_t level) |
Additional Inherited Members | |
Public Types inherited from octomap_server::OctomapServer | |
typedef octomap_msgs::BoundingBoxQuery | BBXSrv |
typedef octomap_msgs::GetOctomap | OctomapSrv |
typedef octomap::OcTree | OcTreeT |
typedef pcl::PointXYZ | PCLPoint |
typedef pcl::PointCloud< pcl::PointXYZ > | PCLPointCloud |
Static Protected Member Functions inherited from octomap_server::OctomapServer | |
static std_msgs::ColorRGBA | heightMapColor (double h) |
static void | updateMaxKey (const octomap::OcTreeKey &in, octomap::OcTreeKey &max) |
static void | updateMinKey (const octomap::OcTreeKey &in, octomap::OcTreeKey &min) |
Definition at line 35 of file OctomapServerMultilayer.h.
|
protected |
Definition at line 49 of file OctomapServerMultilayer.h.
octomap_server::OctomapServerMultilayer::OctomapServerMultilayer | ( | ros::NodeHandle | private_nh_ = ros::NodeHandle("~") | ) |
Definition at line 38 of file OctomapServerMultilayer.cpp.
|
virtual |
Definition at line 97 of file OctomapServerMultilayer.cpp.
|
protectedvirtual |
hook that is called after traversing all nodes
Reimplemented from octomap_server::OctomapServer.
Definition at line 163 of file OctomapServerMultilayer.cpp.
|
protectedvirtual |
hook that is called after traversing all nodes
Reimplemented from octomap_server::OctomapServer.
Definition at line 104 of file OctomapServerMultilayer.cpp.
|
protectedvirtual |
updates the downprojected 2D map as either occupied or free
Reimplemented from octomap_server::OctomapServer.
Definition at line 208 of file OctomapServerMultilayer.cpp.
|
protected |
Definition at line 64 of file OctomapServerMultilayer.h.
|
protected |
Definition at line 63 of file OctomapServerMultilayer.h.
|
protected |
Definition at line 61 of file OctomapServerMultilayer.h.
|
protected |
Definition at line 66 of file OctomapServerMultilayer.h.
|
protected |
Definition at line 60 of file OctomapServerMultilayer.h.