#include <OctomapServer.h>
Public Types | |
typedef octomap_msgs::BoundingBoxQuery | BBXSrv |
typedef octomap_msgs::GetOctomap | OctomapSrv |
typedef octomap::OcTree | OcTreeT |
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 (ros::NodeHandle private_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!) | |
virtual void | handleFreeNode (const OcTreeT::iterator &it) |
hook that is called when traversing free nodes of the updated Octree | |
virtual void | handleFreeNodeInBBX (const OcTreeT::iterator &it) |
hook that is called when traversing free nodes in the updated area (updates 2D map projection here) | |
virtual void | handleNode (const OcTreeT::iterator &it) |
hook that is called when traversing all nodes of the updated Octree (does nothing here) | |
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) | |
virtual void | handleOccupiedNode (const OcTreeT::iterator &it) |
hook that is called when traversing occupied nodes of the updated Octree | |
virtual void | handleOccupiedNodeInBBX (const OcTreeT::iterator &it) |
hook that is called when traversing occupied nodes in the updated area (updates 2D map projection here) | |
virtual void | handlePostNodeTraversal (const ros::Time &rostime) |
hook that is called after traversing all nodes | |
virtual void | handlePreNodeTraversal (const ros::Time &rostime) |
hook that is called before traversing all nodes | |
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. | |
bool | isInUpdateBBX (const octomap::OcTree::iterator &it) const |
Test if key is within update area of map (2D, ignores height) | |
bool | isSpeckleNode (const octomap::OcTreeKey &key) const |
Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution! | |
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 |
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) |
virtual void | update2DMap (const OcTreeT::iterator &it, bool occupied) |
updates the downprojected 2D map as either occupied or free | |
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) |
Protected Attributes | |
std::string | m_baseFrameId |
ros::Publisher | m_binaryMapPub |
ros::ServiceServer | m_clearBBXService |
ros::Publisher | m_cmapPub |
ros::Publisher | m_collisionObjectPub |
std_msgs::ColorRGBA | m_color |
double | m_colorFactor |
std_msgs::ColorRGBA | m_colorFree |
bool | m_compressMap |
bool | m_filterGroundPlane |
bool | m_filterSpeckles |
ros::Publisher | m_fmapPub |
ros::Publisher | m_fmarkerPub |
ros::Publisher | m_fullMapPub |
nav_msgs::OccupancyGrid | m_gridmap |
double | m_groundFilterAngle |
double | m_groundFilterDistance |
double | m_groundFilterPlaneDistance |
bool | m_incrementalUpdate |
octomap::KeyRay | m_keyRay |
bool | m_latchedTopics |
bool | m_mapOriginChanged |
ros::Publisher | m_mapPub |
ros::Publisher | m_markerPub |
double | m_maxRange |
unsigned | m_maxTreeDepth |
double | m_minSizeX |
double | m_minSizeY |
unsigned | m_multires2DScale |
ros::NodeHandle | m_nh |
double | m_occupancyMaxZ |
double | m_occupancyMinZ |
ros::ServiceServer | m_octomapBinaryService |
ros::ServiceServer | m_octomapFullService |
octomap::OcTree * | m_octree |
octomap::OcTreeKey | m_paddedMinKey |
double | m_pointcloudMaxZ |
double | m_pointcloudMinZ |
ros::Publisher | m_pointCloudPub |
message_filters::Subscriber < sensor_msgs::PointCloud2 > * | m_pointCloudSub |
double | m_probHit |
double | m_probMiss |
bool | m_projectCompleteMap |
bool | m_publish2DMap |
bool | m_publishFreeSpace |
dynamic_reconfigure::Server < OctomapServerConfig > | m_reconfigureServer |
double | m_res |
ros::ServiceServer | m_resetService |
tf::TransformListener | m_tfListener |
tf::MessageFilter < sensor_msgs::PointCloud2 > * | m_tfPointCloudSub |
double | m_thresMax |
double | m_thresMin |
unsigned | m_treeDepth |
octomap::OcTreeKey | m_updateBBXMax |
octomap::OcTreeKey | m_updateBBXMin |
bool | m_useHeightMap |
std::string | m_worldFrameId |
Definition at line 71 of file OctomapServer.h.
typedef octomap_msgs::BoundingBoxQuery octomap_server::OctomapServer::BBXSrv |
Definition at line 76 of file OctomapServer.h.
typedef octomap_msgs::GetOctomap octomap_server::OctomapServer::OctomapSrv |
Definition at line 75 of file OctomapServer.h.
Definition at line 78 of file OctomapServer.h.
typedef pcl::PointCloud<pcl::PointXYZ> octomap_server::OctomapServer::PCLPointCloud |
Definition at line 74 of file OctomapServer.h.
octomap_server::OctomapServer::OctomapServer | ( | ros::NodeHandle | private_nh_ = ros::NodeHandle("~") | ) |
Definition at line 37 of file OctomapServer.cpp.
octomap_server::OctomapServer::~OctomapServer | ( | ) | [virtual] |
Definition at line 163 of file OctomapServer.cpp.
void octomap_server::OctomapServer::adjustMapData | ( | nav_msgs::OccupancyGrid & | map, |
const nav_msgs::MapMetaData & | oldMapInfo | ||
) | const [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 1062 of file OctomapServer.cpp.
bool octomap_server::OctomapServer::clearBBXSrv | ( | BBXSrv::Request & | req, |
BBXSrv::Response & | resp | ||
) |
Definition at line 654 of file OctomapServer.cpp.
void octomap_server::OctomapServer::filterGroundPlane | ( | const PCLPointCloud & | pc, |
PCLPointCloud & | ground, | ||
PCLPointCloud & | nonground | ||
) | const [protected] |
label the input cloud "pc" into ground and nonground. Should be in the robot's fixed frame (not world!)
Definition at line 746 of file OctomapServer.cpp.
void octomap_server::OctomapServer::handleFreeNode | ( | const OcTreeT::iterator & | it | ) | [protected, virtual] |
hook that is called when traversing free nodes of the updated Octree
Definition at line 978 of file OctomapServer.cpp.
void octomap_server::OctomapServer::handleFreeNodeInBBX | ( | const OcTreeT::iterator & | it | ) | [protected, virtual] |
hook that is called when traversing free nodes in the updated area (updates 2D map projection here)
Definition at line 992 of file OctomapServer.cpp.
virtual void octomap_server::OctomapServer::handleNode | ( | const OcTreeT::iterator & | it | ) | [inline, protected, virtual] |
hook that is called when traversing all nodes of the updated Octree (does nothing here)
Definition at line 141 of file OctomapServer.h.
virtual void octomap_server::OctomapServer::handleNodeInBBX | ( | const OcTreeT::iterator & | it | ) | [inline, protected, virtual] |
hook that is called when traversing all nodes of the updated Octree in the updated area (does nothing here)
Definition at line 144 of file OctomapServer.h.
void octomap_server::OctomapServer::handleOccupiedNode | ( | const OcTreeT::iterator & | it | ) | [protected, virtual] |
hook that is called when traversing occupied nodes of the updated Octree
Definition at line 971 of file OctomapServer.cpp.
void octomap_server::OctomapServer::handleOccupiedNodeInBBX | ( | const OcTreeT::iterator & | it | ) | [protected, virtual] |
hook that is called when traversing occupied nodes in the updated area (updates 2D map projection here)
Definition at line 985 of file OctomapServer.cpp.
void octomap_server::OctomapServer::handlePostNodeTraversal | ( | const ros::Time & | rostime | ) | [protected, virtual] |
hook that is called after traversing all nodes
Reimplemented in octomap_server::OctomapServerMultilayer.
Definition at line 965 of file OctomapServer.cpp.
void octomap_server::OctomapServer::handlePreNodeTraversal | ( | const ros::Time & | rostime | ) | [protected, virtual] |
hook that is called before traversing all nodes
Reimplemented in octomap_server::OctomapServerMultilayer.
Definition at line 855 of file OctomapServer.cpp.
std_msgs::ColorRGBA octomap_server::OctomapServer::heightMapColor | ( | double | h | ) | [static, protected] |
Definition at line 1103 of file OctomapServer.cpp.
void octomap_server::OctomapServer::insertCloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud | ) | [virtual] |
Definition at line 235 of file OctomapServer.cpp.
void octomap_server::OctomapServer::insertScan | ( | const tf::Point & | sensorOrigin, |
const PCLPointCloud & | ground, | ||
const PCLPointCloud & | nonground | ||
) | [protected, virtual] |
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 315 of file OctomapServer.cpp.
bool octomap_server::OctomapServer::isInUpdateBBX | ( | const octomap::OcTree::iterator & | it | ) | const [inline, protected] |
Test if key is within update area of map (2D, ignores height)
Definition at line 102 of file OctomapServer.h.
bool octomap_server::OctomapServer::isSpeckleNode | ( | const octomap::OcTreeKey & | key | ) | const [protected] |
Find speckle nodes (single occupied voxels with no neighbors). Only works on lowest resolution!
key |
Definition at line 1032 of file OctomapServer.cpp.
bool octomap_server::OctomapServer::mapChanged | ( | const nav_msgs::MapMetaData & | oldMapInfo, |
const nav_msgs::MapMetaData & | newMapInfo | ||
) | [inline, protected] |
Definition at line 182 of file OctomapServer.h.
unsigned octomap_server::OctomapServer::mapIdx | ( | int | i, |
int | j | ||
) | const [inline, protected] |
Definition at line 164 of file OctomapServer.h.
unsigned octomap_server::OctomapServer::mapIdx | ( | const octomap::OcTreeKey & | key | ) | const [inline, protected] |
Definition at line 168 of file OctomapServer.h.
bool octomap_server::OctomapServer::octomapBinarySrv | ( | OctomapSrv::Request & | req, |
OctomapSrv::GetOctomap::Response & | res | ||
) | [virtual] |
Definition at line 628 of file OctomapServer.cpp.
bool octomap_server::OctomapServer::octomapFullSrv | ( | OctomapSrv::Request & | req, |
OctomapSrv::GetOctomap::Response & | res | ||
) | [virtual] |
Definition at line 640 of file OctomapServer.cpp.
bool octomap_server::OctomapServer::openFile | ( | const std::string & | filename | ) | [virtual] |
Definition at line 182 of file OctomapServer.cpp.
void octomap_server::OctomapServer::publishAll | ( | const ros::Time & | rostime = ros::Time::now() | ) | [protected] |
Definition at line 430 of file OctomapServer.cpp.
void octomap_server::OctomapServer::publishBinaryOctoMap | ( | const ros::Time & | rostime = ros::Time::now() | ) | const [protected] |
Definition at line 720 of file OctomapServer.cpp.
void octomap_server::OctomapServer::publishFullOctoMap | ( | const ros::Time & | rostime = ros::Time::now() | ) | const [protected] |
Definition at line 732 of file OctomapServer.cpp.
void octomap_server::OctomapServer::reconfigureCallback | ( | octomap_server::OctomapServerConfig & | config, |
uint32_t | level | ||
) | [protected] |
Definition at line 1052 of file OctomapServer.cpp.
bool octomap_server::OctomapServer::resetSrv | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | resp | ||
) |
Definition at line 672 of file OctomapServer.cpp.
void octomap_server::OctomapServer::update2DMap | ( | const OcTreeT::iterator & | it, |
bool | occupied | ||
) | [protected, virtual] |
updates the downprojected 2D map as either occupied or free
Reimplemented in octomap_server::OctomapServerMultilayer.
Definition at line 999 of file OctomapServer.cpp.
static void octomap_server::OctomapServer::updateMaxKey | ( | const octomap::OcTreeKey & | in, |
octomap::OcTreeKey & | max | ||
) | [inline, static, protected] |
Definition at line 96 of file OctomapServer.h.
static void octomap_server::OctomapServer::updateMinKey | ( | const octomap::OcTreeKey & | in, |
octomap::OcTreeKey & | min | ||
) | [inline, static, protected] |
Definition at line 91 of file OctomapServer.h.
std::string octomap_server::OctomapServer::m_baseFrameId [protected] |
Definition at line 205 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
Definition at line 194 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
std_msgs::ColorRGBA octomap_server::OctomapServer::m_color [protected] |
Definition at line 207 of file OctomapServer.h.
double octomap_server::OctomapServer::m_colorFactor [protected] |
Definition at line 209 of file OctomapServer.h.
std_msgs::ColorRGBA octomap_server::OctomapServer::m_colorFree [protected] |
Definition at line 208 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_compressMap [protected] |
Definition at line 235 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_filterGroundPlane [protected] |
Definition at line 230 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_filterSpeckles [protected] |
Definition at line 228 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
nav_msgs::OccupancyGrid octomap_server::OctomapServer::m_gridmap [protected] |
Definition at line 239 of file OctomapServer.h.
double octomap_server::OctomapServer::m_groundFilterAngle [protected] |
Definition at line 232 of file OctomapServer.h.
double octomap_server::OctomapServer::m_groundFilterDistance [protected] |
Definition at line 231 of file OctomapServer.h.
double octomap_server::OctomapServer::m_groundFilterPlaneDistance [protected] |
Definition at line 233 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_incrementalUpdate [protected] |
Definition at line 238 of file OctomapServer.h.
Definition at line 199 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_latchedTopics [protected] |
Definition at line 211 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_mapOriginChanged [protected] |
Definition at line 241 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
double octomap_server::OctomapServer::m_maxRange [protected] |
Definition at line 203 of file OctomapServer.h.
unsigned octomap_server::OctomapServer::m_maxTreeDepth [protected] |
Definition at line 216 of file OctomapServer.h.
double octomap_server::OctomapServer::m_minSizeX [protected] |
Definition at line 226 of file OctomapServer.h.
double octomap_server::OctomapServer::m_minSizeY [protected] |
Definition at line 227 of file OctomapServer.h.
unsigned octomap_server::OctomapServer::m_multires2DScale [protected] |
Definition at line 243 of file OctomapServer.h.
ros::NodeHandle octomap_server::OctomapServer::m_nh [protected] |
Definition at line 190 of file OctomapServer.h.
double octomap_server::OctomapServer::m_occupancyMaxZ [protected] |
Definition at line 225 of file OctomapServer.h.
double octomap_server::OctomapServer::m_occupancyMinZ [protected] |
Definition at line 224 of file OctomapServer.h.
Definition at line 194 of file OctomapServer.h.
Definition at line 194 of file OctomapServer.h.
octomap::OcTree* octomap_server::OctomapServer::m_octree [protected] |
Definition at line 198 of file OctomapServer.h.
Definition at line 242 of file OctomapServer.h.
double octomap_server::OctomapServer::m_pointcloudMaxZ [protected] |
Definition at line 223 of file OctomapServer.h.
double octomap_server::OctomapServer::m_pointcloudMinZ [protected] |
Definition at line 222 of file OctomapServer.h.
Definition at line 191 of file OctomapServer.h.
message_filters::Subscriber<sensor_msgs::PointCloud2>* octomap_server::OctomapServer::m_pointCloudSub [protected] |
Definition at line 192 of file OctomapServer.h.
double octomap_server::OctomapServer::m_probHit [protected] |
Definition at line 217 of file OctomapServer.h.
double octomap_server::OctomapServer::m_probMiss [protected] |
Definition at line 218 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_projectCompleteMap [protected] |
Definition at line 244 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_publish2DMap [protected] |
Definition at line 240 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_publishFreeSpace [protected] |
Definition at line 212 of file OctomapServer.h.
dynamic_reconfigure::Server<OctomapServerConfig> octomap_server::OctomapServer::m_reconfigureServer [protected] |
Definition at line 196 of file OctomapServer.h.
double octomap_server::OctomapServer::m_res [protected] |
Definition at line 214 of file OctomapServer.h.
Definition at line 194 of file OctomapServer.h.
Definition at line 195 of file OctomapServer.h.
tf::MessageFilter<sensor_msgs::PointCloud2>* octomap_server::OctomapServer::m_tfPointCloudSub [protected] |
Definition at line 193 of file OctomapServer.h.
double octomap_server::OctomapServer::m_thresMax [protected] |
Definition at line 220 of file OctomapServer.h.
double octomap_server::OctomapServer::m_thresMin [protected] |
Definition at line 219 of file OctomapServer.h.
unsigned octomap_server::OctomapServer::m_treeDepth [protected] |
Definition at line 215 of file OctomapServer.h.
Definition at line 201 of file OctomapServer.h.
Definition at line 200 of file OctomapServer.h.
bool octomap_server::OctomapServer::m_useHeightMap [protected] |
Definition at line 206 of file OctomapServer.h.
std::string octomap_server::OctomapServer::m_worldFrameId [protected] |
Definition at line 204 of file OctomapServer.h.