#include <OctomapServer.h>
Public Types | |
typedef octomap_msgs::BoundingBoxQuery | BBXSrv |
typedef octomap_msgs::GetOctomap | OctomapSrv |
typedef octomap::OcTree | OcTreeT |
typedef pcl::PointXYZ | PCLPoint |
typedef pcl::PointCloud< pcl::PointXYZ > | PCLPointCloud |
Public Member Functions | |
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 Member Functions | |
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 | 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 before traversing all nodes 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 (const octomap::OcTreeKey &key) const |
unsigned | mapIdx (int i, int j) 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) |
virtual void | update2DMap (const OcTreeT::iterator &it, bool occupied) |
updates the downprojected 2D map as either occupied or free More... | |
Static Protected Member Functions | |
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 81 of file OctomapServer.h.
typedef octomap_msgs::BoundingBoxQuery octomap_server::OctomapServer::BBXSrv |
Definition at line 94 of file OctomapServer.h.
typedef octomap_msgs::GetOctomap octomap_server::OctomapServer::OctomapSrv |
Definition at line 93 of file OctomapServer.h.
Definition at line 91 of file OctomapServer.h.
typedef pcl::PointXYZ octomap_server::OctomapServer::PCLPoint |
Definition at line 89 of file OctomapServer.h.
typedef pcl::PointCloud<pcl::PointXYZ> octomap_server::OctomapServer::PCLPointCloud |
Definition at line 90 of file OctomapServer.h.
octomap_server::OctomapServer::OctomapServer | ( | const ros::NodeHandle | private_nh_ = ros::NodeHandle("~") , |
const ros::NodeHandle & | nh_ = ros::NodeHandle() |
||
) |
Definition at line 42 of file OctomapServer.cpp.
|
virtual |
Definition at line 191 of file OctomapServer.cpp.
|
protected |
Adjust data of map due to a change in its info properties (origin or size, resolution needs to stay fixed). map already contains the new map info, but the data is stored according to oldMapInfo.
Definition at line 1193 of file OctomapServer.cpp.
bool octomap_server::OctomapServer::clearBBXSrv | ( | BBXSrv::Request & | req, |
BBXSrv::Response & | resp | ||
) |
Definition at line 744 of file OctomapServer.cpp.
|
protected |
label the input cloud "pc" into ground and nonground. Should be in the robot's fixed frame (not world!)
Definition at line 834 of file OctomapServer.cpp.
|
protectedvirtual |
hook that is called when traversing free nodes of the updated Octree
Definition at line 1063 of file OctomapServer.cpp.
|
protectedvirtual |
hook that is called when traversing free nodes in the updated area (updates 2D map projection here)
Definition at line 1075 of file OctomapServer.cpp.
|
inlineprotectedvirtual |
hook that is called when traversing all nodes of the updated Octree (does nothing here)
Definition at line 158 of file OctomapServer.h.
|
inlineprotectedvirtual |
hook that is called when traversing all nodes of the updated Octree in the updated area (does nothing here)
Definition at line 161 of file OctomapServer.h.
|
protectedvirtual |
hook that is called when traversing occupied nodes of the updated Octree
Definition at line 1057 of file OctomapServer.cpp.
|
protectedvirtual |
hook that is called when traversing occupied nodes in the updated area (updates 2D map projection here)
Definition at line 1069 of file OctomapServer.cpp.
|
protectedvirtual |
hook that is called after traversing all nodes
Reimplemented in octomap_server::OctomapServerMultilayer.
Definition at line 1053 of file OctomapServer.cpp.
|
protectedvirtual |
hook that is called before traversing all nodes
Reimplemented in octomap_server::OctomapServerMultilayer.
Definition at line 943 of file OctomapServer.cpp.
|
staticprotected |
Definition at line 1234 of file OctomapServer.cpp.
|
virtual |
Definition at line 263 of file OctomapServer.cpp.
|
protectedvirtual |
update occupancy map with a scan labeled as ground and nonground. The scans should be in the global map frame.
sensorOrigin | origin of the measurements for raycasting |
ground | scan endpoints on the ground plane (only clear space) |
nonground | all other endpoints (clear up to occupied endpoint) |
Reimplemented in octomap_server::TrackingOctomapServer.
Definition at line 357 of file OctomapServer.cpp.
|
inlineprotected |
Test if key is within update area of map (2D, ignores height)
Definition at line 118 of file OctomapServer.h.
|
protected |
Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution!
key |
Definition at line 1113 of file OctomapServer.cpp.
|
inlineprotected |
Definition at line 199 of file OctomapServer.h.
|
inlineprotected |
Definition at line 185 of file OctomapServer.h.
|
inlineprotected |
Definition at line 181 of file OctomapServer.h.
|
virtual |
Definition at line 715 of file OctomapServer.cpp.
|
virtual |
Definition at line 730 of file OctomapServer.cpp.
|
virtual |
Definition at line 210 of file OctomapServer.cpp.
|
protectedvirtual |
Definition at line 497 of file OctomapServer.cpp.
|
protected |
Definition at line 808 of file OctomapServer.cpp.
|
protected |
Definition at line 820 of file OctomapServer.cpp.
|
protected |
Definition at line 489 of file OctomapServer.cpp.
|
protected |
Definition at line 1133 of file OctomapServer.cpp.
bool octomap_server::OctomapServer::resetSrv | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | resp | ||
) |
Definition at line 763 of file OctomapServer.cpp.
|
protectedvirtual |
updates the downprojected 2D map as either occupied or free
Reimplemented in octomap_server::OctomapServerMultilayer.
Definition at line 1081 of file OctomapServer.cpp.
|
inlinestaticprotected |
Definition at line 112 of file OctomapServer.h.
|
inlinestaticprotected |
Definition at line 107 of file OctomapServer.h.
|
protected |
Definition at line 225 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 212 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 227 of file OctomapServer.h.
|
protected |
Definition at line 229 of file OctomapServer.h.
|
protected |
Definition at line 228 of file OctomapServer.h.
|
protected |
Definition at line 255 of file OctomapServer.h.
|
protected |
Definition at line 214 of file OctomapServer.h.
|
protected |
Definition at line 250 of file OctomapServer.h.
|
protected |
Definition at line 248 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 261 of file OctomapServer.h.
|
protected |
Definition at line 252 of file OctomapServer.h.
|
protected |
Definition at line 251 of file OctomapServer.h.
|
protected |
Definition at line 253 of file OctomapServer.h.
|
protected |
Definition at line 260 of file OctomapServer.h.
|
protected |
Definition at line 257 of file OctomapServer.h.
|
protected |
Definition at line 218 of file OctomapServer.h.
|
protected |
Definition at line 231 of file OctomapServer.h.
|
protected |
Definition at line 263 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 223 of file OctomapServer.h.
|
protected |
Definition at line 236 of file OctomapServer.h.
|
protected |
Definition at line 222 of file OctomapServer.h.
|
protected |
Definition at line 246 of file OctomapServer.h.
|
protected |
Definition at line 247 of file OctomapServer.h.
|
protected |
Definition at line 265 of file OctomapServer.h.
|
protected |
Definition at line 207 of file OctomapServer.h.
|
protected |
Definition at line 208 of file OctomapServer.h.
|
protected |
Definition at line 245 of file OctomapServer.h.
|
protected |
Definition at line 244 of file OctomapServer.h.
|
protected |
Definition at line 212 of file OctomapServer.h.
|
protected |
Definition at line 212 of file OctomapServer.h.
|
protected |
Definition at line 217 of file OctomapServer.h.
|
protected |
Definition at line 264 of file OctomapServer.h.
|
protected |
Definition at line 239 of file OctomapServer.h.
|
protected |
Definition at line 241 of file OctomapServer.h.
|
protected |
Definition at line 243 of file OctomapServer.h.
|
protected |
Definition at line 238 of file OctomapServer.h.
|
protected |
Definition at line 240 of file OctomapServer.h.
|
protected |
Definition at line 242 of file OctomapServer.h.
|
protected |
Definition at line 209 of file OctomapServer.h.
|
protected |
Definition at line 210 of file OctomapServer.h.
|
protected |
Definition at line 266 of file OctomapServer.h.
|
protected |
Definition at line 262 of file OctomapServer.h.
|
protected |
Definition at line 232 of file OctomapServer.h.
|
protected |
Definition at line 215 of file OctomapServer.h.
|
protected |
Definition at line 234 of file OctomapServer.h.
|
protected |
Definition at line 212 of file OctomapServer.h.
|
protected |
Definition at line 213 of file OctomapServer.h.
|
protected |
Definition at line 211 of file OctomapServer.h.
|
protected |
Definition at line 235 of file OctomapServer.h.
|
protected |
Definition at line 220 of file OctomapServer.h.
|
protected |
Definition at line 219 of file OctomapServer.h.
|
protected |
Definition at line 267 of file OctomapServer.h.
|
protected |
Definition at line 226 of file OctomapServer.h.
|
protected |
Definition at line 224 of file OctomapServer.h.