$search

octomap_server::TrackingOctomapServer Class Reference

#include <TrackingOctomapServer.h>

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

List of all members.

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

Detailed Description

Definition at line 36 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 83 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:
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.


Member Data Documentation

Definition at line 45 of file TrackingOctomapServer.h.

Definition at line 48 of file TrackingOctomapServer.h.

Definition at line 47 of file TrackingOctomapServer.h.

Definition at line 49 of file TrackingOctomapServer.h.

Definition at line 50 of file TrackingOctomapServer.h.

Definition at line 46 of file TrackingOctomapServer.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


octomap_server
Author(s): Armin Hornung
autogenerated on Tue Mar 5 12:07:38 2013