29 #ifndef IMAGE_DISPLAY_BASE_H 30 #define IMAGE_DISPLAY_BASE_H 34 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 37 # include <sensor_msgs/Image.h> 69 virtual void setTopic(
const QString &topic,
const QString &datatype );
108 virtual void processMessage(
const sensor_msgs::Image::ConstPtr& msg) = 0;
112 boost::scoped_ptr<image_transport::ImageTransport>
it_;
133 #endif // IMAGE_DISPLAY_BASE_H
void scanForTransportSubscriberPlugins()
void fillTransportOptionList(EnumProperty *property)
Fill list of available and working transport options.
virtual void unsubscribe()
Property specialized to provide max/min enforcement for integers.
ImageDisplayBase()
Constructor.
virtual void fixedFrameChanged()
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
BoolProperty * unreliable_property_
virtual void processMessage(const sensor_msgs::Image::ConstPtr &msg)=0
Implement this to process the contents of a message.
IntProperty * queue_size_property_
virtual void subscribe()
ROS topic management.
uint32_t messages_received_
Display subclass for subscribing and displaying to image messages.
void enableTFFilter(std::string &targetFrame)
Enabling TF filtering by defining a target frame.
virtual void updateQueueSize()
Update queue size of tf filter.
virtual void onInitialize()
Override this function to do subclass-specific initialization.
virtual void reset()
Reset display.
EnumProperty * transport_property_
RosTopicProperty * topic_property_
virtual void updateTopic()
Update topic and resubscribe.
Property specialized to provide getter for booleans.
boost::shared_ptr< tf::MessageFilter< sensor_msgs::Image > > tf_filter_
std::set< std::string > transport_plugin_types_
void incomingMessage(const sensor_msgs::Image::ConstPtr &msg)
Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage().
boost::shared_ptr< image_transport::SubscriberFilter > sub_
boost::scoped_ptr< image_transport::ImageTransport > it_
virtual void setTopic(const QString &topic, const QString &datatype)
Set the ROS topic to listen to for this display.
virtual ~ImageDisplayBase()