#include <ROSInterface.h>
Public Member Functions | |
virtual void | createSubscriber (ros::NodeHandle &nh) |
virtual void | processData (const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &msg) |
ROSPointCloudLoader (std::string topic, osg::ref_ptr< osg::Group > root, unsigned int mask, bool del) | |
~ROSPointCloudLoader () | |
Private Attributes | |
bool | deleteLastPCD |
osg::ref_ptr < osg::MatrixTransform > | lastPCD |
unsigned int | nodeMask |
osg::ref_ptr< osg::Group > | scene_root |
Definition at line 158 of file ROSInterface.h.
ROSPointCloudLoader::ROSPointCloudLoader | ( | std::string | topic, |
osg::ref_ptr< osg::Group > | root, | ||
unsigned int | mask, | ||
bool | del | ||
) |
Definition at line 238 of file ROSInterface.cpp.
Definition at line 282 of file ROSInterface.cpp.
void ROSPointCloudLoader::createSubscriber | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements ROSSubscriberInterface.
Definition at line 244 of file ROSInterface.cpp.
void ROSPointCloudLoader::processData | ( | const pcl::PointCloud< pcl::PointXYZ >::ConstPtr & | msg | ) | [virtual] |
Definition at line 250 of file ROSInterface.cpp.
bool ROSPointCloudLoader::deleteLastPCD [private] |
Definition at line 163 of file ROSInterface.h.
osg::ref_ptr< osg::MatrixTransform > ROSPointCloudLoader::lastPCD [private] |
Definition at line 162 of file ROSInterface.h.
unsigned int ROSPointCloudLoader::nodeMask [private] |
Definition at line 161 of file ROSInterface.h.
osg::ref_ptr<osg::Group> ROSPointCloudLoader::scene_root [private] |
Definition at line 160 of file ROSInterface.h.