$search
#include <point_cloud2_display.h>
Public Member Functions | |
virtual void | createProperties () |
Called from setPropertyManager, gives the display a chance to create some properties immediately. | |
virtual void | fixedFrameChanged () |
Called from within setFixedFrame, notifying child classes that the fixed frame has changed. | |
const std::string & | getTopic () |
PointCloud2Display (const std::string &name, VisualizationManager *manager) | |
void | setTopic (const std::string &topic) |
virtual void | targetFrameChanged () |
Called from within setTargetFrame, notifying child classes that the target frame has changed. | |
~PointCloud2Display () | |
Protected Member Functions | |
void | incomingCloudCallback (const sensor_msgs::PointCloud2ConstPtr &cloud) |
ROS callback for an incoming point cloud message. | |
virtual void | onDisable () |
Derived classes override this to do the actual work of disabling themselves. | |
virtual void | onEnable () |
Derived classes override this to do the actual work of enabling themselves. | |
void | subscribe () |
Subscribes to the topic set by setTopic(). | |
void | unsubscribe () |
Unsubscribes from the current topic. | |
Protected Attributes | |
message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_ |
tf::MessageFilter < sensor_msgs::PointCloud2 > | tf_filter_ |
std::string | topic_ |
The PointCloud topic set by setTopic(). | |
ROSTopicStringPropertyWPtr | topic_property_ |
Definition at line 62 of file point_cloud2_display.h.
rviz::PointCloud2Display::PointCloud2Display | ( | const std::string & | name, | |
VisualizationManager * | manager | |||
) |
Definition at line 49 of file point_cloud2_display.cpp.
rviz::PointCloud2Display::~PointCloud2Display | ( | ) |
Definition at line 58 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::createProperties | ( | ) | [virtual] |
Called from setPropertyManager, gives the display a chance to create some properties immediately.
Once this function is called, the property_manager_ member is valid and will stay valid
Reimplemented from rviz::PointCloudBase.
Definition at line 171 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::fixedFrameChanged | ( | ) | [virtual] |
Called from within setFixedFrame, notifying child classes that the fixed frame has changed.
Reimplemented from rviz::PointCloudBase.
Definition at line 164 of file point_cloud2_display.cpp.
const std::string& rviz::PointCloud2Display::getTopic | ( | ) | [inline] |
Definition at line 78 of file point_cloud2_display.h.
void rviz::PointCloud2Display::incomingCloudCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloud | ) | [protected] |
ROS callback for an incoming point cloud message.
Definition at line 106 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Reimplemented from rviz::PointCloudBase.
Definition at line 83 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Reimplemented from rviz::PointCloudBase.
Definition at line 76 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::setTopic | ( | const std::string & | topic | ) |
Set the incoming PointCloud topic
topic | The topic we should listen to |
Definition at line 64 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::subscribe | ( | ) | [protected] |
Subscribes to the topic set by setTopic().
Definition at line 91 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::targetFrameChanged | ( | ) | [virtual] |
Called from within setTargetFrame, notifying child classes that the target frame has changed.
Implements rviz::Display.
Definition at line 160 of file point_cloud2_display.cpp.
void rviz::PointCloud2Display::unsubscribe | ( | ) | [protected] |
Unsubscribes from the current topic.
Definition at line 101 of file point_cloud2_display.cpp.
Definition at line 100 of file point_cloud2_display.h.
Definition at line 101 of file point_cloud2_display.h.
std::string rviz::PointCloud2Display::topic_ [protected] |
The PointCloud topic set by setTopic().
Definition at line 98 of file point_cloud2_display.h.
ROSTopicStringPropertyWPtr rviz::PointCloud2Display::topic_property_ [protected] |
Definition at line 103 of file point_cloud2_display.h.