#include <point_cloud_common.h>
| Public Member Functions | |
| void | clear () | 
| CloudInfo () | |
| ~CloudInfo () | |
| Public Attributes | |
| boost::shared_ptr< PointCloud > | cloud_ | 
| Ogre::SceneManager * | manager_ | 
| sensor_msgs::PointCloud2ConstPtr | message_ | 
| Ogre::Quaternion | orientation_ | 
| Ogre::Vector3 | position_ | 
| ros::Time | receive_time_ | 
| Ogre::SceneNode * | scene_node_ | 
| PointCloudSelectionHandlerPtr | selection_handler_ | 
| std::vector< PointCloud::Point > | transformed_points_ | 
Definition at line 89 of file point_cloud_common.h.
| rviz::PointCloudCommon::CloudInfo::CloudInfo | ( | ) | 
Definition at line 295 of file point_cloud_common.cpp.
| rviz::PointCloudCommon::CloudInfo::~CloudInfo | ( | ) | 
Definition at line 300 of file point_cloud_common.cpp.
| void rviz::PointCloudCommon::CloudInfo::clear | ( | ) | 
Definition at line 305 of file point_cloud_common.cpp.
| boost::shared_ptr<PointCloud> rviz::PointCloudCommon::CloudInfo::cloud_ | 
Definition at line 104 of file point_cloud_common.h.
| Ogre::SceneManager* rviz::PointCloudCommon::CloudInfo::manager_ | 
Definition at line 99 of file point_cloud_common.h.
| sensor_msgs::PointCloud2ConstPtr rviz::PointCloudCommon::CloudInfo::message_ | 
Definition at line 101 of file point_cloud_common.h.
| Ogre::Quaternion rviz::PointCloudCommon::CloudInfo::orientation_ | 
Definition at line 109 of file point_cloud_common.h.
| Ogre::Vector3 rviz::PointCloudCommon::CloudInfo::position_ | 
Definition at line 110 of file point_cloud_common.h.
| ros::Time rviz::PointCloudCommon::CloudInfo::receive_time_ | 
Definition at line 97 of file point_cloud_common.h.
| Ogre::SceneNode* rviz::PointCloudCommon::CloudInfo::scene_node_ | 
Definition at line 103 of file point_cloud_common.h.
| PointCloudSelectionHandlerPtr rviz::PointCloudCommon::CloudInfo::selection_handler_ | 
Definition at line 105 of file point_cloud_common.h.
| std::vector<PointCloud::Point> rviz::PointCloudCommon::CloudInfo::transformed_points_ | 
Definition at line 107 of file point_cloud_common.h.