Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
octomap_server::TrackingOctomapServer Class Reference

#include <TrackingOctomapServer.h>

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

Public Member Functions

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...
 
void trackCallback (sensor_msgs::PointCloud2Ptr cloud)
 
 TrackingOctomapServer (const std::string &filename="")
 
virtual ~TrackingOctomapServer ()
 
- 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 Member Functions

void trackChanges ()
 
- 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 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...
 
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...
 

Protected Attributes

std::string change_id_frame
 
bool listen_changes
 
int min_change_pub
 
ros::Publisher pubChangeSet
 
ros::Publisher pubFreeChangeSet
 
ros::Subscriber subChangeSet
 
ros::Subscriber subFreeChanges
 
bool track_changes
 
- 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 37 of file TrackingOctomapServer.h.

Constructor & Destructor Documentation

octomap_server::TrackingOctomapServer::TrackingOctomapServer ( const std::string &  filename = "")

Definition at line 37 of file TrackingOctomapServer.cpp.

octomap_server::TrackingOctomapServer::~TrackingOctomapServer ( )
virtual

Definition at line 86 of file TrackingOctomapServer.cpp.

Member Function Documentation

void octomap_server::TrackingOctomapServer::insertScan ( const tf::Point sensorOrigin,
const PCLPointCloud ground,
const PCLPointCloud nonground 
)
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 from octomap_server::OctomapServer.

Definition at line 89 of file TrackingOctomapServer.cpp.

void octomap_server::TrackingOctomapServer::trackCallback ( sensor_msgs::PointCloud2Ptr  cloud)

Definition at line 141 of file TrackingOctomapServer.cpp.

void octomap_server::TrackingOctomapServer::trackChanges ( )
protected

Definition at line 97 of file TrackingOctomapServer.cpp.

Member Data Documentation

std::string octomap_server::TrackingOctomapServer::change_id_frame
protected

Definition at line 51 of file TrackingOctomapServer.h.

bool octomap_server::TrackingOctomapServer::listen_changes
protected

Definition at line 48 of file TrackingOctomapServer.h.

int octomap_server::TrackingOctomapServer::min_change_pub
protected

Definition at line 50 of file TrackingOctomapServer.h.

ros::Publisher octomap_server::TrackingOctomapServer::pubChangeSet
protected

Definition at line 53 of file TrackingOctomapServer.h.

ros::Publisher octomap_server::TrackingOctomapServer::pubFreeChangeSet
protected

Definition at line 52 of file TrackingOctomapServer.h.

ros::Subscriber octomap_server::TrackingOctomapServer::subChangeSet
protected

Definition at line 54 of file TrackingOctomapServer.h.

ros::Subscriber octomap_server::TrackingOctomapServer::subFreeChanges
protected

Definition at line 55 of file TrackingOctomapServer.h.

bool octomap_server::TrackingOctomapServer::track_changes
protected

Definition at line 49 of file TrackingOctomapServer.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