Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
octomap_server::OctomapServerMultilayer Class Reference

#include <OctomapServerMultilayer.h>

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

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< ProjectedMapMultilevelGrid
 

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 reconfigureCallback (octomap_server::OctomapServerConfig &config, uint32_t level)
 

Protected Attributes

std::vector< double > m_armLinkOffsets
 
std::vector< std::string > m_armLinks
 
ros::Subscriber m_attachedObjectsSub
 
MultilevelGrid m_multiGridmap
 
std::vector< ros::Publisher * > m_multiMapPub
 
- Protected Attributes inherited from octomap_server::OctomapServer
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
 

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)
 

Detailed Description

Definition at line 35 of file OctomapServerMultilayer.h.

Member Typedef Documentation

Definition at line 49 of file OctomapServerMultilayer.h.

Constructor & Destructor Documentation

octomap_server::OctomapServerMultilayer::OctomapServerMultilayer ( ros::NodeHandle  private_nh_ = ros::NodeHandle("~"))

Definition at line 38 of file OctomapServerMultilayer.cpp.

octomap_server::OctomapServerMultilayer::~OctomapServerMultilayer ( )
virtual

Definition at line 97 of file OctomapServerMultilayer.cpp.

Member Function Documentation

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

hook that is called after traversing all nodes

Reimplemented from octomap_server::OctomapServer.

Definition at line 163 of file OctomapServerMultilayer.cpp.

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

hook that is called after traversing all nodes

Reimplemented from octomap_server::OctomapServer.

Definition at line 104 of file OctomapServerMultilayer.cpp.

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

updates the downprojected 2D map as either occupied or free

Reimplemented from octomap_server::OctomapServer.

Definition at line 208 of file OctomapServerMultilayer.cpp.

Member Data Documentation

std::vector<double> octomap_server::OctomapServerMultilayer::m_armLinkOffsets
protected

Definition at line 64 of file OctomapServerMultilayer.h.

std::vector<std::string> octomap_server::OctomapServerMultilayer::m_armLinks
protected

Definition at line 63 of file OctomapServerMultilayer.h.

ros::Subscriber octomap_server::OctomapServerMultilayer::m_attachedObjectsSub
protected

Definition at line 61 of file OctomapServerMultilayer.h.

MultilevelGrid octomap_server::OctomapServerMultilayer::m_multiGridmap
protected

Definition at line 66 of file OctomapServerMultilayer.h.

std::vector<ros::Publisher*> octomap_server::OctomapServerMultilayer::m_multiMapPub
protected

Definition at line 60 of file OctomapServerMultilayer.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