29 #ifndef MESSAGE_FILTER_DISPLAY_H 30 #define MESSAGE_FILTER_DISPLAY_H 42 #include "rviz/rviz_export.h" 55 topic_property_ =
new RosTopicProperty(
"Topic",
"",
"",
"",
this, SLOT(updateTopic()));
56 unreliable_property_ =
57 new BoolProperty(
"Unreliable",
false,
"Prefer UDP topic transport",
this, SLOT(updateTopic()));
61 virtual void updateTopic() = 0;
74 template <
class MessageType>
85 QString message_type = QString::fromStdString(ros::message_traits::datatype<MessageType>());
86 topic_property_->setMessageType(message_type);
87 topic_property_->setDescription(message_type +
" topic to subscribe to.");
93 fixed_frame_.toStdString(), 10, update_nh_);
96 tf_filter_->registerCallback(
98 context_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_,
this);
114 update_nh_.getCallbackQueue()->removeByID((uint64_t)tf_filter_);
115 messages_received_ = 0;
118 void setTopic(
const QString& topic,
const QString& )
override 120 topic_property_->setString(topic);
129 context_->queueRender();
143 if (unreliable_property_->getBool())
147 sub_.subscribe(update_nh_, topic_property_->getTopicStd(), 10, transport_hint);
174 tf_filter_->setTargetFrame(fixed_frame_.toStdString());
183 if (!msg || !isEnabled())
188 ++messages_received_;
189 setStatus(
StatusProperty::Ok,
"Topic", QString::number(messages_received_) +
" messages received");
197 virtual void processMessage(
const typename MessageType::ConstPtr& msg) = 0;
206 #endif // MESSAGE_FILTER_DISPLAY_H tf2_ros::MessageFilter< MessageType > * tf_filter_
void reset() override
Called to tell the display to clear its state.
void setTopic(const QString &topic, const QString &) override
Set the ROS topic to listen to for this display.
TransportHints & reliable()
MessageFilterDisplay< MessageType > MFDClass
Convenience typedef so subclasses don't have to use the long templated class name to refer to their s...
~MessageFilterDisplay() override
RosTopicProperty * topic_property_
virtual void unsubscribe()
TransportHints & unreliable()
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
virtual void reset()
Called to tell the display to clear its state.
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
void updateTopic() override
BoolProperty * unreliable_property_
uint32_t messages_received_
Property specialized to provide getter for booleans.
void onInitialize() override
Override this function to do subclass-specific initialization.
void incomingMessage(const typename MessageType::ConstPtr &msg)
Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage().
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
message_filters::Subscriber< MessageType > sub_
Helper superclass for MessageFilterDisplay, needed because Qt's moc and c++ templates don't work nice...