1 #ifndef DATASTREAM_ROS_TOPIC_H 2 #define DATASTREAM_ROS_TOPIC_H 11 #include <rosgraph_msgs/Clock.h> 19 Q_PLUGIN_METADATA(IID
"facontidavide.PlotJuggler3.DataStreamer")
25 virtual bool start(QStringList* selected_datasources)
override;
33 virtual const char*
name()
const override 35 return "ROS Topic Subscriber";
38 virtual bool xmlSaveState(QDomDocument& doc, QDomElement& parent_element)
const override;
40 virtual bool xmlLoadState(
const QDomElement& parent_element)
override;
80 std::unique_ptr<RosCompositeParser>
_parser;
92 #endif // DATALOAD_CSV_H void topicCallback(const RosIntrospection::ShapeShifter::ConstPtr &msg, const std::string &topic_name)
RosIntrospection::SubstitutionRuleMap _rules
virtual const std::vector< QAction * > & availableActions() override
void extractInitialSamples()
virtual void shutdown() override
std::unordered_map< std::string, PlotDataAny > _user_defined_buffers
std::vector< QAction * > _available_actions
std::map< ROSType, std::vector< SubstitutionRule > > SubstitutionRuleMap
std::unique_ptr< RosCompositeParser > _parser
virtual bool start(QStringList *selected_datasources) override
std::map< std::string, int > _msg_index
virtual bool xmlLoadState(const QDomElement &parent_element) override
virtual const char * name() const override
virtual ~DataStreamROS() override
QAction * _action_saveAny
virtual bool xmlSaveState(QDomDocument &doc, QDomElement &parent_element) const override
virtual bool isRunning() const override
std::map< std::string, ros::Subscriber > _subscribers
std::shared_ptr< ros::AsyncSpinner > _spinner
QAction * _action_saveIntoRosbag