statepublisher_rostopic.h
Go to the documentation of this file.
00001 #ifndef STATE_PUBLISHER_ROSTOPIC_H
00002 #define STATE_PUBLISHER_ROSTOPIC_H
00003 
00004 #include <QObject>
00005 #include <QtPlugin>
00006 #include <map>
00007 #include <ros/ros.h>
00008 #include <ros_type_introspection/ros_introspection.hpp>
00009 #include <tf/transform_broadcaster.h>
00010 #include "PlotJuggler/statepublisher_base.h"
00011 #include "../shape_shifter_factory.hpp"
00012 #include <rosbag/bag.h>
00013 
00014 class  TopicPublisherROS: public QObject, StatePublisher
00015 {
00016     Q_OBJECT
00017     Q_PLUGIN_METADATA(IID "com.icarustechnology.PlotJuggler.StatePublisher" "../statepublisher.json")
00018     Q_INTERFACES(StatePublisher)
00019 
00020 public:
00021     TopicPublisherROS();
00022     virtual ~TopicPublisherROS() override;
00023 
00024     virtual void updateState(double current_time) override;
00025 
00026     virtual const char* name() const override { return "TopicPublisherROS"; }
00027 
00028     virtual bool enabled() const override { return _enabled; }
00029 
00030     void setParentMenu(QMenu *menu, QAction *action) override;
00031 
00032     virtual void play(double interval)  override;
00033 
00034 public slots:
00035     virtual void setEnabled(bool enabled) override;
00036 
00037     void filterDialog(bool autoconfirm);
00038 
00039 private:
00040 
00041     void broadcastTF(double current_time);
00042 
00043     std::map<std::string, ros::Publisher> _publishers;
00044     bool _enabled;
00045     ros::NodeHandlePtr _node;
00046     bool _publish_clock;
00047     std::unique_ptr<tf::TransformBroadcaster> _tf_publisher;
00048     ros::Publisher _clock_publisher;
00049 
00050     QAction* _enable_self_action;
00051     QAction* _select_topics_to_publish;
00052 
00053     std::unordered_map<std::string,bool> _topics_to_publish;
00054 
00055     bool toPublish(const std::string& topic_name);
00056 
00057     double previous_time;
00058 
00059     int _previous_play_index;
00060 
00061     void publishAnyMsg(const rosbag::MessageInstance& msg_instance);
00062 };
00063 
00064 #endif // DATALOAD_CSV_H


plotjuggler
Author(s): Davide Faconti
autogenerated on Wed Jul 3 2019 19:28:05