datastream_ROS.h
Go to the documentation of this file.
1 #ifndef DATASTREAM_ROS_TOPIC_H
2 #define DATASTREAM_ROS_TOPIC_H
3 
4 #include <QtPlugin>
5 #include <QAction>
6 #include <QTimer>
7 #include <thread>
11 #include <rosgraph_msgs/Clock.h>
12 #include "../dialog_select_ros_topics.h"
13 #include "../RosMsgParsers/ros_parser.h"
14 
16 {
17  Q_OBJECT
18  Q_PLUGIN_METADATA(IID "com.icarustechnology.PlotJuggler.DataStreamer" "../datastreamer.json")
19  Q_INTERFACES(DataStreamer)
20 
21 public:
22 
23  DataStreamROS();
24 
25  virtual bool start(QStringList* selected_datasources) override;
26 
27  virtual void shutdown() override;
28 
29  virtual bool isRunning() const override;
30 
31  virtual ~DataStreamROS() override;
32 
33  virtual const char* name() const override { return "ROS Topic Streamer"; }
34 
35  virtual bool xmlSaveState(QDomDocument &doc, QDomElement &parent_element) const override;
36 
37  virtual bool xmlLoadState(const QDomElement &parent_element ) override;
38 
39  virtual void addActionsToParentMenu( QMenu* menu ) override;
40 
41  virtual std::vector<QString> appendData(PlotDataMapRef& destination) override
42  {
43  _destination_data = &destination;
44  return DataStreamer::appendData(destination);
45  }
46 
47 private:
48 
50 
51  void topicCallback(const topic_tools::ShapeShifter::ConstPtr& msg, const std::string &topic_name);
52 
53  void clockCallback(const rosgraph_msgs::Clock::ConstPtr& msg);
54 
55  void extractInitialSamples();
56 
57  void timerCallback();
58 
59  void subscribe();
60 
61  void saveDefaultSettings();
62 
63  void loadDefaultSettings();
64 
65  bool _running;
66 
67  std::shared_ptr<ros::AsyncSpinner> _spinner;
68 
69  double _initial_time;
70 
71  std::string _prefix;
72 
74 
75  std::map<std::string, ros::Subscriber> _subscribers;
76 
78 
80 
82 
83  std::map<std::string, int> _msg_index;
84 
86 
88 
89  QTimer* _periodic_timer;
90 
92 
94 
95 private:
96 
97  static void saveIntoRosbag(const PlotDataMapRef& data);
98 };
99 
100 #endif // DATALOAD_CSV_H
void topicCallback(const topic_tools::ShapeShifter::ConstPtr &msg, const std::string &topic_name)
RosIntrospection::SubstitutionRuleMap _rules
QTimer * _periodic_timer
ros::NodeHandlePtr _node
void extractInitialSamples()
virtual void addActionsToParentMenu(QMenu *menu) override
void saveDefaultSettings()
void loadDefaultSettings()
double _initial_time
std::string _prefix
virtual void shutdown() override
std::map< ROSType, std::vector< SubstitutionRule > > SubstitutionRuleMap
PlotDataMapRef * _destination_data
virtual bool start(QStringList *selected_datasources) override
std::map< std::string, int > _msg_index
bool _roscore_disconnection_already_notified
virtual bool xmlLoadState(const QDomElement &parent_element) override
virtual const char * name() const override
virtual std::vector< QString > appendData(PlotDataMapRef &destination) override
virtual ~DataStreamROS() override
double _prev_clock_time
RosMessageParser _ros_parser
virtual bool xmlSaveState(QDomDocument &doc, QDomElement &parent_element) const override
DialogSelectRosTopics::Configuration _config
virtual bool isRunning() const override
The DataStreamer base class to create your own plugin.
void clockCallback(const rosgraph_msgs::Clock::ConstPtr &msg)
virtual std::vector< QString > appendData(PlotDataMapRef &destination)
std::map< std::string, ros::Subscriber > _subscribers
static void saveIntoRosbag(const PlotDataMapRef &data)
std::shared_ptr< ros::AsyncSpinner > _spinner
QAction * _action_saveIntoRosbag


plotjuggler
Author(s): Davide Faconti
autogenerated on Sat Jul 6 2019 03:44:17