Display subclass for subscribing and displaying to image messages. More...
#include <image_display_base.h>

| Public Member Functions | |
| ImageDisplayBase () | |
| Constructor. | |
| virtual void | setTopic (const QString &topic, const QString &datatype) | 
| Set the ROS topic to listen to for this display. | |
| virtual | ~ImageDisplayBase () | 
| Protected Slots | |
| void | fillTransportOptionList (EnumProperty *property) | 
| Fill list of available and working transport options. | |
| virtual void | updateQueueSize () | 
| Update queue size of tf filter. | |
| virtual void | updateTopic () | 
| Update topic and resubscribe. | |
| Protected Member Functions | |
| void | enableTFFilter (std::string &targetFrame) | 
| Enabling TF filtering by defining a target frame. | |
| virtual void | fixedFrameChanged () | 
| Called by setFixedFrame(). Override to respond to changes to fixed_frame_. | |
| void | incomingMessage (const sensor_msgs::Image::ConstPtr &msg) | 
| Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage(). | |
| virtual void | onInitialize () | 
| Override this function to do subclass-specific initialization. | |
| virtual void | processMessage (const sensor_msgs::Image::ConstPtr &msg)=0 | 
| Implement this to process the contents of a message. | |
| virtual void | reset () | 
| Reset display. | |
| void | scanForTransportSubscriberPlugins () | 
| virtual void | subscribe () | 
| ROS topic management. | |
| virtual void | unsubscribe () | 
| Protected Attributes | |
| boost::scoped_ptr < image_transport::ImageTransport > | it_ | 
| uint32_t | messages_received_ | 
| IntProperty * | queue_size_property_ | 
| boost::shared_ptr < image_transport::SubscriberFilter > | sub_ | 
| std::string | targetFrame_ | 
| boost::shared_ptr < tf::MessageFilter < sensor_msgs::Image > > | tf_filter_ | 
| RosTopicProperty * | topic_property_ | 
| std::string | transport_ | 
| std::set< std::string > | transport_plugin_types_ | 
| EnumProperty * | transport_property_ | 
| BoolProperty * | unreliable_property_ | 
Display subclass for subscribing and displaying to image messages.
This class brings together some common things used for subscribing and displaying image messages in Display types. It has a tf::MessageFilter and image_tranport::SubscriberFilter to filter incoming image messages, and it handles subscribing and unsubscribing when the display is enabled or disabled.
Definition at line 60 of file image_display_base.h.
Constructor.
Definition at line 45 of file image_display_base.cpp.
| rviz::ImageDisplayBase::~ImageDisplayBase | ( | ) |  [virtual] | 
Definition at line 77 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::enableTFFilter | ( | std::string & | targetFrame | ) |  [inline, protected] | 
Enabling TF filtering by defining a target frame.
Definition at line 88 of file image_display_base.h.
| void rviz::ImageDisplayBase::fillTransportOptionList | ( | EnumProperty * | property | ) |  [protected, slot] | 
Fill list of available and working transport options.
Definition at line 253 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::fixedFrameChanged | ( | ) |  [protected, virtual] | 
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
Reimplemented from rviz::Display.
Reimplemented in rviz::CameraDisplay.
Definition at line 204 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::incomingMessage | ( | const sensor_msgs::Image::ConstPtr & | msg | ) |  [protected] | 
Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage().
Definition at line 113 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::onInitialize | ( | ) |  [protected, virtual] | 
Override this function to do subclass-specific initialization.
This is called after vis_manager_ and scene_manager_ are set, and before load() or setEnabled().
setName() may or may not have been called before this.
Reimplemented from rviz::Display.
Reimplemented in rviz::CameraDisplay, and rviz::ImageDisplay.
Definition at line 82 of file image_display_base.cpp.
| virtual void rviz::ImageDisplayBase::processMessage | ( | const sensor_msgs::Image::ConstPtr & | msg | ) |  [protected, pure virtual] | 
Implement this to process the contents of a message.
This is called by incomingMessage().
Implemented in rviz::CameraDisplay, and rviz::ImageDisplay.
| void rviz::ImageDisplayBase::reset | ( | ) |  [protected, virtual] | 
Reset display.
Reimplemented from rviz::Display.
Reimplemented in rviz::CameraDisplay, and rviz::ImageDisplay.
Definition at line 129 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::scanForTransportSubscriberPlugins | ( | ) |  [protected] | 
Definition at line 213 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::setTopic | ( | const QString & | topic, | 
| const QString & | datatype | ||
| ) |  [virtual] | 
Set the ROS topic to listen to for this display.
By default, do nothing. Subclasses should override this method if they subscribe to a single ROS topic.
setTopic() is used by the "New display by topic" window; it is called with a user selected topic and its type.
| topic | The published topic to be visualized. | 
| datatype | The datatype of the topic. | 
Reimplemented from rviz::Display.
Definition at line 88 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::subscribe | ( | ) |  [protected, virtual] | 
ROS topic management.
Reimplemented in rviz::CameraDisplay.
Definition at line 144 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::unsubscribe | ( | ) |  [protected, virtual] | 
Reimplemented in rviz::CameraDisplay.
Definition at line 198 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::updateQueueSize | ( | ) |  [protected, virtual, slot] | 
Update queue size of tf filter.
Reimplemented in rviz::CameraDisplay.
Definition at line 137 of file image_display_base.cpp.
| void rviz::ImageDisplayBase::updateTopic | ( | ) |  [protected, virtual, slot] | 
Update topic and resubscribe.
Definition at line 245 of file image_display_base.cpp.
| boost::scoped_ptr<image_transport::ImageTransport> rviz::ImageDisplayBase::it_  [protected] | 
Definition at line 112 of file image_display_base.h.
| uint32_t rviz::ImageDisplayBase::messages_received_  [protected] | 
Definition at line 118 of file image_display_base.h.
| IntProperty* rviz::ImageDisplayBase::queue_size_property_  [protected] | 
Definition at line 122 of file image_display_base.h.
| boost::shared_ptr<image_transport::SubscriberFilter> rviz::ImageDisplayBase::sub_  [protected] | 
Definition at line 113 of file image_display_base.h.
| std::string rviz::ImageDisplayBase::targetFrame_  [protected] | 
Definition at line 116 of file image_display_base.h.
| boost::shared_ptr<tf::MessageFilter<sensor_msgs::Image> > rviz::ImageDisplayBase::tf_filter_  [protected] | 
Definition at line 114 of file image_display_base.h.
| RosTopicProperty* rviz::ImageDisplayBase::topic_property_  [protected] | 
Definition at line 120 of file image_display_base.h.
| std::string rviz::ImageDisplayBase::transport_  [protected] | 
Definition at line 124 of file image_display_base.h.
| std::set<std::string> rviz::ImageDisplayBase::transport_plugin_types_  [protected] | 
Definition at line 126 of file image_display_base.h.
| EnumProperty* rviz::ImageDisplayBase::transport_property_  [protected] | 
Definition at line 121 of file image_display_base.h.
| BoolProperty* rviz::ImageDisplayBase::unreliable_property_  [protected] | 
Definition at line 128 of file image_display_base.h.