#include <TrackingOctomapServer.h>
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. | |
void | trackCallback (sensor_msgs::PointCloud2Ptr cloud) |
TrackingOctomapServer (const std::string &filename="") | |
virtual | ~TrackingOctomapServer () |
Protected Member Functions | |
void | trackChanges () |
Protected Attributes | |
bool | listen_changes |
ros::Publisher | pubChangeSet |
ros::Publisher | pubFreeChangeSet |
ros::Subscriber | subChangeSet |
ros::Subscriber | subFreeChanges |
bool | track_changes |
Definition at line 37 of file TrackingOctomapServer.h.
octomap_server::TrackingOctomapServer::TrackingOctomapServer | ( | const std::string & | filename = "" | ) |
Definition at line 37 of file TrackingOctomapServer.cpp.
Definition at line 83 of file TrackingOctomapServer.cpp.
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.
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 from octomap_server::OctomapServer.
Definition at line 86 of file TrackingOctomapServer.cpp.
void octomap_server::TrackingOctomapServer::trackCallback | ( | sensor_msgs::PointCloud2Ptr | cloud | ) |
Definition at line 133 of file TrackingOctomapServer.cpp.
void octomap_server::TrackingOctomapServer::trackChanges | ( | ) | [protected] |
Definition at line 94 of file TrackingOctomapServer.cpp.
Definition at line 48 of file TrackingOctomapServer.h.
Definition at line 51 of file TrackingOctomapServer.h.
Definition at line 50 of file TrackingOctomapServer.h.
Definition at line 52 of file TrackingOctomapServer.h.
Definition at line 53 of file TrackingOctomapServer.h.
Definition at line 49 of file TrackingOctomapServer.h.