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 () |
Override to handle changes to fixed_frame_. This base class implementation does nothing. | |
int | getQueueSize () |
const std::string & | getTopic () |
LaserScanDisplay () | |
virtual void | onInitialize () |
Override this function to do subclass-specific initialization. | |
void | setQueueSize (int size) |
void | setTopic (const std::string &topic) |
~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_ |
IntPropertyWPtr | queue_size_property_ |
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.
Definition at line 48 of file laser_scan_display.cpp.
Definition at line 53 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::createProperties | ( | ) | [virtual] |
Called from setPropertyManager, gives the display a chance to create some properties immediately.
When this function is called, the property_manager_ member is valid and will stay valid
Reimplemented from rviz::PointCloudBase.
Definition at line 173 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::fixedFrameChanged | ( | ) | [virtual] |
Override to handle changes to fixed_frame_. This base class implementation does nothing.
Reimplemented from rviz::PointCloudBase.
Definition at line 166 of file laser_scan_display.cpp.
Definition at line 81 of file laser_scan_display.cpp.
const std::string& rviz::LaserScanDisplay::getTopic | ( | ) | [inline] |
Definition at line 80 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 140 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 108 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 101 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::onInitialize | ( | ) | [virtual] |
Override this function to do subclass-specific initialization.
This is called after vis_manager_ and scene_manager_ are set.
Reimplemented from rviz::PointCloudBase.
Definition at line 61 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::setQueueSize | ( | int | size | ) |
Set the incoming message queue size.
Definition at line 72 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 86 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::subscribe | ( | ) | [protected] |
Subscribes to the topic set by setTopic()
Definition at line 115 of file laser_scan_display.cpp.
void rviz::LaserScanDisplay::unsubscribe | ( | ) | [protected] |
Unsubscribes from the current topic.
Definition at line 133 of file laser_scan_display.cpp.
Definition at line 112 of file laser_scan_display.h.
Definition at line 110 of file laser_scan_display.h.
IntPropertyWPtr rviz::LaserScanDisplay::queue_size_property_ [protected] |
Definition at line 113 of file laser_scan_display.h.
message_filters::Subscriber<sensor_msgs::LaserScan> rviz::LaserScanDisplay::sub_ [protected] |
Definition at line 105 of file laser_scan_display.h.
tf::MessageFilter<sensor_msgs::LaserScan>* rviz::LaserScanDisplay::tf_filter_ [protected] |
Definition at line 106 of file laser_scan_display.h.
std::string rviz::LaserScanDisplay::topic_ [protected] |
The PointCloud topic set by setTopic()
Definition at line 104 of file laser_scan_display.h.
ROSTopicStringPropertyWPtr rviz::LaserScanDisplay::topic_property_ [protected] |
Definition at line 108 of file laser_scan_display.h.