$search
#include <cloud_handler.h>
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::NodeHandle * | nh_ |
ros::Publisher | pub_point_ |
tf::TransformListener * | tfl_ |
std::string | topic_ |
Definition at line 43 of file cloud_handler.h.
CloudContainer::CloudContainer | ( | ros::NodeHandle * | nh, | |
tf::TransformListener * | tfl, | |||
std::string | name, | |||
const std::string & | topic | |||
) |
Definition at line 38 of file cloud_handler.cpp.
CloudContainer::~CloudContainer | ( | ) |
Definition at line 48 of file cloud_handler.cpp.
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.
Definition at line 70 of file cloud_handler.h.
std::string CloudContainer::name_ [private] |
Definition at line 72 of file cloud_handler.h.
ros::NodeHandle* CloudContainer::nh_ [private] |
Definition at line 73 of file cloud_handler.h.
ros::Publisher CloudContainer::pub_point_ [private] |
Definition at line 74 of file cloud_handler.h.
tf::TransformListener* CloudContainer::tfl_ [private] |
Definition at line 75 of file cloud_handler.h.
std::string CloudContainer::topic_ [private] |
Definition at line 72 of file cloud_handler.h.