Public Types | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes
octomap_server::OctomapServer Class Reference

#include <OctomapServer.h>

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

List of all members.

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 (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 OcTreeT::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
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

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
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 76 of file OctomapServer.h.


Member Typedef Documentation

typedef octomap_msgs::BoundingBoxQuery octomap_server::OctomapServer::BBXSrv

Definition at line 89 of file OctomapServer.h.

typedef octomap_msgs::GetOctomap octomap_server::OctomapServer::OctomapSrv

Definition at line 88 of file OctomapServer.h.

Definition at line 86 of file OctomapServer.h.

Definition at line 84 of file OctomapServer.h.

Definition at line 85 of file OctomapServer.h.


Constructor & Destructor Documentation

Definition at line 42 of file OctomapServer.cpp.

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

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

Definition at line 736 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 827 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 1059 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 1073 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 152 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 155 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 1052 of file OctomapServer.cpp.

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

Definition at line 1066 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 1046 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 936 of file OctomapServer.cpp.

std_msgs::ColorRGBA octomap_server::OctomapServer::heightMapColor ( double  h) [static, protected]

Definition at line 1232 of file OctomapServer.cpp.

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

Definition at line 262 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.

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

bool octomap_server::OctomapServer::isInUpdateBBX ( const OcTreeT::iterator it) const [inline, protected]

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

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

bool octomap_server::OctomapServer::mapChanged ( const nav_msgs::MapMetaData &  oldMapInfo,
const nav_msgs::MapMetaData &  newMapInfo 
) [inline, protected]

Definition at line 193 of file OctomapServer.h.

unsigned octomap_server::OctomapServer::mapIdx ( int  i,
int  j 
) const [inline, protected]

Definition at line 175 of file OctomapServer.h.

unsigned octomap_server::OctomapServer::mapIdx ( const octomap::OcTreeKey key) const [inline, protected]

Definition at line 179 of file OctomapServer.h.

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

Definition at line 707 of file OctomapServer.cpp.

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

Definition at line 722 of file OctomapServer.cpp.

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

Definition at line 209 of file OctomapServer.cpp.

void octomap_server::OctomapServer::publishAll ( const ros::Time rostime = ros::Time::now()) [protected, virtual]

Definition at line 488 of file OctomapServer.cpp.

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

Definition at line 801 of file OctomapServer.cpp.

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

Definition at line 813 of file OctomapServer.cpp.

void octomap_server::OctomapServer::reconfigureCallback ( octomap_server::OctomapServerConfig &  config,
uint32_t  level 
) [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 755 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 1080 of file OctomapServer.cpp.

static void octomap_server::OctomapServer::updateMaxKey ( const octomap::OcTreeKey in,
octomap::OcTreeKey max 
) [inline, static, protected]

Definition at line 107 of file OctomapServer.h.

static void octomap_server::OctomapServer::updateMinKey ( const octomap::OcTreeKey in,
octomap::OcTreeKey min 
) [inline, static, protected]

Definition at line 102 of file OctomapServer.h.


Member Data Documentation

Definition at line 217 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

Definition at line 205 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

std_msgs::ColorRGBA octomap_server::OctomapServer::m_color [protected]

Definition at line 219 of file OctomapServer.h.

Definition at line 221 of file OctomapServer.h.

std_msgs::ColorRGBA octomap_server::OctomapServer::m_colorFree [protected]

Definition at line 220 of file OctomapServer.h.

Definition at line 247 of file OctomapServer.h.

boost::recursive_mutex octomap_server::OctomapServer::m_config_mutex [protected]

Definition at line 207 of file OctomapServer.h.

Definition at line 242 of file OctomapServer.h.

Definition at line 240 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

nav_msgs::OccupancyGrid octomap_server::OctomapServer::m_gridmap [protected]

Definition at line 253 of file OctomapServer.h.

Definition at line 244 of file OctomapServer.h.

Definition at line 243 of file OctomapServer.h.

Definition at line 245 of file OctomapServer.h.

Definition at line 252 of file OctomapServer.h.

Definition at line 249 of file OctomapServer.h.

Definition at line 211 of file OctomapServer.h.

Definition at line 223 of file OctomapServer.h.

Definition at line 255 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

Definition at line 215 of file OctomapServer.h.

Definition at line 228 of file OctomapServer.h.

Definition at line 238 of file OctomapServer.h.

Definition at line 239 of file OctomapServer.h.

Definition at line 257 of file OctomapServer.h.

Definition at line 201 of file OctomapServer.h.

Definition at line 237 of file OctomapServer.h.

Definition at line 236 of file OctomapServer.h.

Definition at line 205 of file OctomapServer.h.

Definition at line 205 of file OctomapServer.h.

Definition at line 210 of file OctomapServer.h.

Definition at line 256 of file OctomapServer.h.

Definition at line 231 of file OctomapServer.h.

Definition at line 233 of file OctomapServer.h.

Definition at line 235 of file OctomapServer.h.

Definition at line 230 of file OctomapServer.h.

Definition at line 232 of file OctomapServer.h.

Definition at line 234 of file OctomapServer.h.

Definition at line 202 of file OctomapServer.h.

Definition at line 203 of file OctomapServer.h.

Definition at line 258 of file OctomapServer.h.

Definition at line 254 of file OctomapServer.h.

Definition at line 224 of file OctomapServer.h.

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

Definition at line 208 of file OctomapServer.h.

Definition at line 226 of file OctomapServer.h.

Definition at line 205 of file OctomapServer.h.

Definition at line 206 of file OctomapServer.h.

Definition at line 204 of file OctomapServer.h.

Definition at line 227 of file OctomapServer.h.

Definition at line 213 of file OctomapServer.h.

Definition at line 212 of file OctomapServer.h.

Definition at line 259 of file OctomapServer.h.

Definition at line 218 of file OctomapServer.h.

Definition at line 216 of file OctomapServer.h.


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


octomap_server
Author(s): Armin Hornung
autogenerated on Wed Nov 23 2016 03:40:03