Public Types | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
octomap_server::OctomapServer Class Reference

#include <OctomapServer.h>

Inheritance diagram for octomap_server::OctomapServer:
Inheritance graph
[legend]

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 (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)
 
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)
 

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
 
boost::recursive_mutex m_config_mutex
 
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
 
bool m_initConfig
 
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
 
ros::NodeHandle m_nh_private
 
double m_occupancyMaxZ
 
double m_occupancyMinZ
 
ros::ServiceServer m_octomapBinaryService
 
ros::ServiceServer m_octomapFullService
 
OcTreeTm_octree
 
octomap::OcTreeKey m_paddedMinKey
 
double m_pointcloudMaxX
 
double m_pointcloudMaxY
 
double m_pointcloudMaxZ
 
double m_pointcloudMinX
 
double m_pointcloudMinY
 
double m_pointcloudMinZ
 
ros::Publisher m_pointCloudPub
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointCloudSub
 
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
 
unsigned m_treeDepth
 
octomap::OcTreeKey m_updateBBXMax
 
octomap::OcTreeKey m_updateBBXMin
 
bool m_useColoredMap
 
bool m_useHeightMap
 
std::string m_worldFrameId
 

Detailed Description

Definition at line 81 of file OctomapServer.h.

Member Typedef Documentation

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.

Definition at line 89 of file OctomapServer.h.

Definition at line 90 of file OctomapServer.h.

Constructor & Destructor Documentation

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.

octomap_server::OctomapServer::~OctomapServer ( )
virtual

Definition at line 189 of file OctomapServer.cpp.

Member Function Documentation

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 1188 of file OctomapServer.cpp.

bool octomap_server::OctomapServer::clearBBXSrv ( BBXSrv::Request &  req,
BBXSrv::Response &  resp 
)

Definition at line 733 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 824 of file OctomapServer.cpp.

void octomap_server::OctomapServer::handleFreeNode ( const OcTreeT::iterator it)
protectedvirtual

hook that is called when traversing free nodes of the updated Octree

Definition at line 1056 of file OctomapServer.cpp.

void octomap_server::OctomapServer::handleFreeNodeInBBX ( const OcTreeT::iterator it)
protectedvirtual

hook that is called when traversing free nodes in the updated area (updates 2D map projection here)

Definition at line 1070 of file OctomapServer.cpp.

virtual void octomap_server::OctomapServer::handleNode ( const OcTreeT::iterator it)
inlineprotectedvirtual

hook that is called when traversing all nodes of the updated Octree (does nothing here)

Definition at line 157 of file OctomapServer.h.

virtual void octomap_server::OctomapServer::handleNodeInBBX ( const OcTreeT::iterator it)
inlineprotectedvirtual

hook that is called when traversing all nodes of the updated Octree in the updated area (does nothing here)

Definition at line 160 of file OctomapServer.h.

void octomap_server::OctomapServer::handleOccupiedNode ( const OcTreeT::iterator it)
protectedvirtual

hook that is called when traversing occupied nodes of the updated Octree

Definition at line 1049 of file OctomapServer.cpp.

void octomap_server::OctomapServer::handleOccupiedNodeInBBX ( const OcTreeT::iterator it)
protectedvirtual

hook that is called when traversing occupied nodes in the updated area (updates 2D map projection here)

Definition at line 1063 of file OctomapServer.cpp.

void octomap_server::OctomapServer::handlePostNodeTraversal ( const ros::Time rostime)
protectedvirtual

hook that is called after traversing all nodes

Reimplemented in octomap_server::OctomapServerMultilayer.

Definition at line 1043 of file OctomapServer.cpp.

void octomap_server::OctomapServer::handlePreNodeTraversal ( const ros::Time rostime)
protectedvirtual

hook that is called before traversing all nodes

Reimplemented in octomap_server::OctomapServerMultilayer.

Definition at line 933 of file OctomapServer.cpp.

std_msgs::ColorRGBA octomap_server::OctomapServer::heightMapColor ( double  h)
staticprotected

Definition at line 1229 of file OctomapServer.cpp.

void octomap_server::OctomapServer::insertCloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud)
virtual

Definition at line 261 of file OctomapServer.cpp.

void octomap_server::OctomapServer::insertScan ( const tf::Point sensorOrigin,
const PCLPointCloud ground,
const PCLPointCloud nonground 
)
protectedvirtual

update occupancy map with a scan labeled as ground and nonground. The scans should be in the global map frame.

Parameters
sensorOriginorigin of the measurements for raycasting
groundscan endpoints on the ground plane (only clear space)
nongroundall other endpoints (clear up to occupied endpoint)

Reimplemented in octomap_server::TrackingOctomapServer.

Definition at line 355 of file OctomapServer.cpp.

bool octomap_server::OctomapServer::isInUpdateBBX ( const OcTreeT::iterator it) const
inlineprotected

Test if key is within update area of map (2D, ignores height)

Definition at line 118 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!

Parameters
key
Returns

Definition at line 1110 of file OctomapServer.cpp.

bool octomap_server::OctomapServer::mapChanged ( const nav_msgs::MapMetaData &  oldMapInfo,
const nav_msgs::MapMetaData &  newMapInfo 
)
inlineprotected

Definition at line 198 of file OctomapServer.h.

unsigned octomap_server::OctomapServer::mapIdx ( int  i,
int  j 
) const
inlineprotected

Definition at line 180 of file OctomapServer.h.

unsigned octomap_server::OctomapServer::mapIdx ( const octomap::OcTreeKey key) const
inlineprotected

Definition at line 184 of file OctomapServer.h.

bool octomap_server::OctomapServer::octomapBinarySrv ( OctomapSrv::Request &  req,
OctomapSrv::GetOctomap::Response &  res 
)
virtual

Definition at line 704 of file OctomapServer.cpp.

bool octomap_server::OctomapServer::octomapFullSrv ( OctomapSrv::Request &  req,
OctomapSrv::GetOctomap::Response &  res 
)
virtual

Definition at line 719 of file OctomapServer.cpp.

bool octomap_server::OctomapServer::openFile ( const std::string &  filename)
virtual

Definition at line 208 of file OctomapServer.cpp.

void octomap_server::OctomapServer::publishAll ( const ros::Time rostime = ros::Time::now())
protectedvirtual

Definition at line 483 of file OctomapServer.cpp.

void octomap_server::OctomapServer::publishBinaryOctoMap ( const ros::Time rostime = ros::Time::now()) const
protected

Definition at line 798 of file OctomapServer.cpp.

void octomap_server::OctomapServer::publishFullOctoMap ( const ros::Time rostime = ros::Time::now()) const
protected

Definition at line 810 of file OctomapServer.cpp.

void octomap_server::OctomapServer::reconfigureCallback ( octomap_server::OctomapServerConfig &  config,
uint32_t  level 
)
protected

Definition at line 1130 of file OctomapServer.cpp.

bool octomap_server::OctomapServer::resetSrv ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  resp 
)

Definition at line 752 of file OctomapServer.cpp.

void octomap_server::OctomapServer::update2DMap ( const OcTreeT::iterator it,
bool  occupied 
)
protectedvirtual

updates the downprojected 2D map as either occupied or free

Reimplemented in octomap_server::OctomapServerMultilayer.

Definition at line 1077 of file OctomapServer.cpp.

static void octomap_server::OctomapServer::updateMaxKey ( const octomap::OcTreeKey in,
octomap::OcTreeKey max 
)
inlinestaticprotected

Definition at line 112 of file OctomapServer.h.

static void octomap_server::OctomapServer::updateMinKey ( const octomap::OcTreeKey in,
octomap::OcTreeKey min 
)
inlinestaticprotected

Definition at line 107 of file OctomapServer.h.

Member Data Documentation

std::string octomap_server::OctomapServer::m_baseFrameId
protected

Definition at line 223 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_binaryMapPub
protected

Definition at line 208 of file OctomapServer.h.

ros::ServiceServer octomap_server::OctomapServer::m_clearBBXService
protected

Definition at line 211 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_cmapPub
protected

Definition at line 208 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_collisionObjectPub
protected

Definition at line 208 of file OctomapServer.h.

std_msgs::ColorRGBA octomap_server::OctomapServer::m_color
protected

Definition at line 225 of file OctomapServer.h.

double octomap_server::OctomapServer::m_colorFactor
protected

Definition at line 227 of file OctomapServer.h.

std_msgs::ColorRGBA octomap_server::OctomapServer::m_colorFree
protected

Definition at line 226 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_compressMap
protected

Definition at line 253 of file OctomapServer.h.

boost::recursive_mutex octomap_server::OctomapServer::m_config_mutex
protected

Definition at line 213 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_filterGroundPlane
protected

Definition at line 248 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_filterSpeckles
protected

Definition at line 246 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_fmapPub
protected

Definition at line 208 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_fmarkerPub
protected

Definition at line 208 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_fullMapPub
protected

Definition at line 208 of file OctomapServer.h.

nav_msgs::OccupancyGrid octomap_server::OctomapServer::m_gridmap
protected

Definition at line 259 of file OctomapServer.h.

double octomap_server::OctomapServer::m_groundFilterAngle
protected

Definition at line 250 of file OctomapServer.h.

double octomap_server::OctomapServer::m_groundFilterDistance
protected

Definition at line 249 of file OctomapServer.h.

double octomap_server::OctomapServer::m_groundFilterPlaneDistance
protected

Definition at line 251 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_incrementalUpdate
protected

Definition at line 258 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_initConfig
protected

Definition at line 255 of file OctomapServer.h.

octomap::KeyRay octomap_server::OctomapServer::m_keyRay
protected

Definition at line 217 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_latchedTopics
protected

Definition at line 229 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_mapOriginChanged
protected

Definition at line 261 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_mapPub
protected

Definition at line 208 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_markerPub
protected

Definition at line 208 of file OctomapServer.h.

double octomap_server::OctomapServer::m_maxRange
protected

Definition at line 221 of file OctomapServer.h.

unsigned octomap_server::OctomapServer::m_maxTreeDepth
protected

Definition at line 234 of file OctomapServer.h.

double octomap_server::OctomapServer::m_minSizeX
protected

Definition at line 244 of file OctomapServer.h.

double octomap_server::OctomapServer::m_minSizeY
protected

Definition at line 245 of file OctomapServer.h.

unsigned octomap_server::OctomapServer::m_multires2DScale
protected

Definition at line 263 of file OctomapServer.h.

ros::NodeHandle octomap_server::OctomapServer::m_nh
protected

Definition at line 206 of file OctomapServer.h.

ros::NodeHandle octomap_server::OctomapServer::m_nh_private
protected

Definition at line 207 of file OctomapServer.h.

double octomap_server::OctomapServer::m_occupancyMaxZ
protected

Definition at line 243 of file OctomapServer.h.

double octomap_server::OctomapServer::m_occupancyMinZ
protected

Definition at line 242 of file OctomapServer.h.

ros::ServiceServer octomap_server::OctomapServer::m_octomapBinaryService
protected

Definition at line 211 of file OctomapServer.h.

ros::ServiceServer octomap_server::OctomapServer::m_octomapFullService
protected

Definition at line 211 of file OctomapServer.h.

OcTreeT* octomap_server::OctomapServer::m_octree
protected

Definition at line 216 of file OctomapServer.h.

octomap::OcTreeKey octomap_server::OctomapServer::m_paddedMinKey
protected

Definition at line 262 of file OctomapServer.h.

double octomap_server::OctomapServer::m_pointcloudMaxX
protected

Definition at line 237 of file OctomapServer.h.

double octomap_server::OctomapServer::m_pointcloudMaxY
protected

Definition at line 239 of file OctomapServer.h.

double octomap_server::OctomapServer::m_pointcloudMaxZ
protected

Definition at line 241 of file OctomapServer.h.

double octomap_server::OctomapServer::m_pointcloudMinX
protected

Definition at line 236 of file OctomapServer.h.

double octomap_server::OctomapServer::m_pointcloudMinY
protected

Definition at line 238 of file OctomapServer.h.

double octomap_server::OctomapServer::m_pointcloudMinZ
protected

Definition at line 240 of file OctomapServer.h.

ros::Publisher octomap_server::OctomapServer::m_pointCloudPub
protected

Definition at line 208 of file OctomapServer.h.

message_filters::Subscriber<sensor_msgs::PointCloud2>* octomap_server::OctomapServer::m_pointCloudSub
protected

Definition at line 209 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_projectCompleteMap
protected

Definition at line 264 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_publish2DMap
protected

Definition at line 260 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_publishFreeSpace
protected

Definition at line 230 of file OctomapServer.h.

dynamic_reconfigure::Server<OctomapServerConfig> octomap_server::OctomapServer::m_reconfigureServer
protected

Definition at line 214 of file OctomapServer.h.

double octomap_server::OctomapServer::m_res
protected

Definition at line 232 of file OctomapServer.h.

ros::ServiceServer octomap_server::OctomapServer::m_resetService
protected

Definition at line 211 of file OctomapServer.h.

tf::TransformListener octomap_server::OctomapServer::m_tfListener
protected

Definition at line 212 of file OctomapServer.h.

tf::MessageFilter<sensor_msgs::PointCloud2>* octomap_server::OctomapServer::m_tfPointCloudSub
protected

Definition at line 210 of file OctomapServer.h.

unsigned octomap_server::OctomapServer::m_treeDepth
protected

Definition at line 233 of file OctomapServer.h.

octomap::OcTreeKey octomap_server::OctomapServer::m_updateBBXMax
protected

Definition at line 219 of file OctomapServer.h.

octomap::OcTreeKey octomap_server::OctomapServer::m_updateBBXMin
protected

Definition at line 218 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_useColoredMap
protected

Definition at line 265 of file OctomapServer.h.

bool octomap_server::OctomapServer::m_useHeightMap
protected

Definition at line 224 of file OctomapServer.h.

std::string octomap_server::OctomapServer::m_worldFrameId
protected

Definition at line 222 of file OctomapServer.h.


The documentation for this class was generated from the following files:


octomap_server
Author(s): Armin Hornung
autogenerated on Tue Jan 26 2021 03:27:07