statepublisher_rostopic.h
Go to the documentation of this file.
1 #ifndef STATE_PUBLISHER_ROSTOPIC_H
2 #define STATE_PUBLISHER_ROSTOPIC_H
3 
4 #include <QObject>
5 #include <QtPlugin>
6 #include <map>
7 #include <ros/ros.h>
11 #include "../shape_shifter_factory.hpp"
12 #include <rosbag/bag.h>
13 
14 class TopicPublisherROS: public QObject, StatePublisher
15 {
16  Q_OBJECT
17  Q_PLUGIN_METADATA(IID "com.icarustechnology.PlotJuggler.StatePublisher" "../statepublisher.json")
18  Q_INTERFACES(StatePublisher)
19 
20 public:
22  virtual ~TopicPublisherROS() override;
23 
24  virtual void updateState(double current_time) override;
25 
26  virtual const char* name() const override { return "TopicPublisherROS"; }
27 
28  virtual bool enabled() const override { return _enabled; }
29 
30  void setParentMenu(QMenu *menu, QAction *action) override;
31 
32  virtual void play(double interval) override;
33 
34 public slots:
35  virtual void setEnabled(bool enabled) override;
36 
37  void filterDialog(bool autoconfirm);
38 
39 private:
40 
41  void broadcastTF(double current_time);
42 
43  std::map<std::string, ros::Publisher> _publishers;
44  bool _enabled;
47  std::unique_ptr<tf::TransformBroadcaster> _tf_publisher;
49 
52 
53  std::unordered_map<std::string,bool> _topics_to_publish;
54 
55  bool toPublish(const std::string& topic_name);
56 
57  double previous_time;
58 
60 
61  void publishAnyMsg(const rosbag::MessageInstance& msg_instance);
62 };
63 
64 #endif // DATALOAD_CSV_H
bool toPublish(const std::string &topic_name)
void filterDialog(bool autoconfirm)
virtual bool enabled() const override
virtual const char * name() const override
void broadcastTF(double current_time)
ros::Publisher _clock_publisher
void setParentMenu(QMenu *menu, QAction *action) override
ros::NodeHandlePtr _node
virtual ~TopicPublisherROS() override
virtual void updateState(double current_time) override
std::unordered_map< std::string, bool > _topics_to_publish
action
std::map< std::string, ros::Publisher > _publishers
virtual void setEnabled(bool enabled) override
virtual void play(double interval) override
std::unique_ptr< tf::TransformBroadcaster > _tf_publisher
void publishAnyMsg(const rosbag::MessageInstance &msg_instance)


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