Public Member Functions | Private Attributes
CloudContainer Class Reference

#include <cloud_handler.h>

List of all members.

Public Member Functions

void changeFrame (const std::string &frame)
 Use TF to transform the internally stored cloud to this target frame.
void clear ()
 Clear the cloud stored in this object.
 CloudContainer (ros::NodeHandle *nh, tf::TransformListener *tfl, std::string name, const std::string &topic)
bool get (sensor_msgs::PointCloud2 &cloud, const std::string &frame)
 Get the cloud stored in this object.
bool refresh (const std::string &topic, const std::string &frame)
 Refresh the cloud stored in this object.
void set (const sensor_msgs::PointCloud2 &cloud, const std::string &frame)
 Set the cloud stored in this object.
 ~CloudContainer ()

Private Attributes

sensor_msgs::PointCloud2 cloud_
std::string name_
ros::NodeHandlenh_
ros::Publisher pub_point_
tf::TransformListenertfl_
std::string topic_

Detailed Description

Definition at line 43 of file cloud_handler.h.


Constructor & Destructor Documentation

CloudContainer::CloudContainer ( ros::NodeHandle nh,
tf::TransformListener tfl,
std::string  name,
const std::string &  topic 
)

Definition at line 38 of file cloud_handler.cpp.

Definition at line 48 of file cloud_handler.cpp.


Member Function Documentation

void CloudContainer::changeFrame ( const std::string &  frame)

Use TF to transform the internally stored cloud to this target frame.

Definition at line 57 of file cloud_handler.cpp.

void CloudContainer::clear ( void  )

Clear the cloud stored in this object.

Definition at line 52 of file cloud_handler.cpp.

bool CloudContainer::get ( sensor_msgs::PointCloud2 &  cloud,
const std::string &  frame 
)

Get the cloud stored in this object.

Definition at line 84 of file cloud_handler.cpp.

bool CloudContainer::refresh ( const std::string &  topic,
const std::string &  frame 
)

Refresh the cloud stored in this object.

Definition at line 117 of file cloud_handler.cpp.

void CloudContainer::set ( const sensor_msgs::PointCloud2 &  cloud,
const std::string &  frame 
)

Set the cloud stored in this object.

Definition at line 77 of file cloud_handler.cpp.


Member Data Documentation

sensor_msgs::PointCloud2 CloudContainer::cloud_ [private]

Definition at line 70 of file cloud_handler.h.

std::string CloudContainer::name_ [private]

Definition at line 72 of file cloud_handler.h.

Definition at line 73 of file cloud_handler.h.

Definition at line 74 of file cloud_handler.h.

Definition at line 75 of file cloud_handler.h.

std::string CloudContainer::topic_ [private]

Definition at line 72 of file cloud_handler.h.


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


point_cloud_server
Author(s): Adam Leeper
autogenerated on Thu Jan 2 2014 11:39:34