Public Member Functions | Protected Slots | Protected Member Functions | Protected Attributes
rviz::ImageDisplayBase Class Reference

Display subclass for subscribing and displaying to image messages. More...

#include <image_display_base.h>

Inheritance diagram for rviz::ImageDisplayBase:
Inheritance graph
[legend]

List of all members.

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_
IntPropertyqueue_size_property_
boost::shared_ptr
< image_transport::SubscriberFilter
sub_
std::string targetFrame_
boost::shared_ptr
< tf::MessageFilter
< sensor_msgs::Image > > 
tf_filter_
RosTopicPropertytopic_property_
std::string transport_
std::set< std::string > transport_plugin_types_
EnumPropertytransport_property_

Detailed Description

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 & Destructor Documentation

Constructor.

Definition at line 45 of file image_display_base.cpp.

Definition at line 72 of file image_display_base.cpp.


Member Function Documentation

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 238 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 189 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 108 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 77 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 124 of file image_display_base.cpp.

Definition at line 198 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.

Parameters:
topicThe published topic to be visualized.
datatypeThe datatype of the topic.

Reimplemented from rviz::Display.

Definition at line 83 of file image_display_base.cpp.

void rviz::ImageDisplayBase::subscribe ( ) [protected, virtual]

ROS topic management.

Reimplemented in rviz::CameraDisplay.

Definition at line 139 of file image_display_base.cpp.

void rviz::ImageDisplayBase::unsubscribe ( ) [protected, virtual]

Reimplemented in rviz::CameraDisplay.

Definition at line 183 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 132 of file image_display_base.cpp.

void rviz::ImageDisplayBase::updateTopic ( ) [protected, virtual, slot]

Update topic and resubscribe.

Definition at line 230 of file image_display_base.cpp.


Member Data Documentation

Definition at line 112 of file image_display_base.h.

Definition at line 118 of file image_display_base.h.

Definition at line 122 of file image_display_base.h.

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.

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.

Definition at line 126 of file image_display_base.h.

Definition at line 121 of file image_display_base.h.


The documentation for this class was generated from the following files:


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:29