$search
Visualizes a laser scan, received as a sensor_msgs::LaserScan. More...
#include <laser_scan_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 () |
LaserScanDisplay (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. | |
~LaserScanDisplay () | |
Protected Member Functions | |
void | incomingScanCallback (const sensor_msgs::LaserScan::ConstPtr &scan) |
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 | |
ros::Duration | filter_tolerance_ |
laser_geometry::LaserProjection * | projector_ |
message_filters::Subscriber < sensor_msgs::LaserScan > | sub_ |
tf::MessageFilter < sensor_msgs::LaserScan > | tf_filter_ |
std::string | topic_ |
The PointCloud topic set by setTopic(). | |
ROSTopicStringPropertyWPtr | topic_property_ |
Visualizes a laser scan, received as a sensor_msgs::LaserScan.
Definition at line 63 of file laser_scan_display.h.
rviz::LaserScanDisplay::LaserScanDisplay | ( | const std::string & | name, | |
VisualizationManager * | manager | |||
) |
Definition at line 48 of file laser_scan_display.cpp.
rviz::LaserScanDisplay::~LaserScanDisplay | ( | ) |
Definition at line 59 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::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 149 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::fixedFrameChanged | ( | ) | [virtual] |
Called from within setFixedFrame, notifying child classes that the fixed frame has changed.
Reimplemented from rviz::PointCloudBase.
Definition at line 142 of file laser_scan_display.cpp.
const std::string& rviz::LaserScanDisplay::getTopic | ( | ) | [inline] |
Definition at line 79 of file laser_scan_display.h.
void rviz::LaserScanDisplay::incomingScanCallback | ( | const sensor_msgs::LaserScan::ConstPtr & | scan | ) | [protected] |
ROS callback for an incoming point cloud message.
Definition at line 112 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::onDisable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of disabling themselves.
Reimplemented from rviz::PointCloudBase.
Definition at line 88 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::onEnable | ( | ) | [protected, virtual] |
Derived classes override this to do the actual work of enabling themselves.
Reimplemented from rviz::PointCloudBase.
Definition at line 81 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::setTopic | ( | const std::string & | topic | ) |
Set the incoming PointCloud topic
topic | The topic we should listen to |
Definition at line 66 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::subscribe | ( | ) | [protected] |
Subscribes to the topic set by setTopic().
Definition at line 95 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::targetFrameChanged | ( | ) | [virtual] |
Called from within setTargetFrame, notifying child classes that the target frame has changed.
Implements rviz::Display.
Definition at line 138 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::unsubscribe | ( | ) | [protected] |
Unsubscribes from the current topic.
Definition at line 105 of file laser_scan_display.cpp.
Definition at line 107 of file laser_scan_display.h.
Definition at line 105 of file laser_scan_display.h.
Definition at line 100 of file laser_scan_display.h.
Definition at line 101 of file laser_scan_display.h.
std::string rviz::LaserScanDisplay::topic_ [protected] |
The PointCloud topic set by setTopic().
Definition at line 99 of file laser_scan_display.h.
ROSTopicStringPropertyWPtr rviz::LaserScanDisplay::topic_property_ [protected] |
Definition at line 103 of file laser_scan_display.h.