topic_data.hpp
Go to the documentation of this file.
1 #ifndef GRAPH_RVIZ_PLUGIN_TOPIC_DATA_HPP
2 #define GRAPH_RVIZ_PLUGIN_TOPIC_DATA_HPP
3 
4 #include <deque>
5 #include <exception>
7 #include <mutex>
8 #include <QMessageBox>
9 #include <QObject>
10 #include <QVector>
11 #include <ros/ros.h>
12 #include <ros/time.h>
13 #include <sensor_msgs/Image.h>
14 #include <std_msgs/Bool.h>
15 #include <std_msgs/Duration.h>
16 #include <std_msgs/Float32.h>
17 #include <std_msgs/Float64.h>
18 #include <std_msgs/Int16.h>
19 #include <std_msgs/Int32.h>
20 #include <std_msgs/Int64.h>
21 #include <std_msgs/Int8.h>
22 #include <std_msgs/String.h>
23 #include <std_msgs/Time.h>
24 #include <std_msgs/UInt16.h>
25 #include <std_msgs/UInt32.h>
26 #include <std_msgs/UInt64.h>
27 #include <std_msgs/UInt8.h>
28 
29 namespace graph_rviz_plugin
30 {
31 
32 class TopicData : public QObject
33 {
34 Q_OBJECT
35 public:
36  TopicData(std::string topic_name,
37  std::string topic_type,
38  std::shared_ptr<ros::NodeHandle>,
39  QObject *parent = nullptr);
40 
41  ~TopicData();
42  std::shared_ptr<ros::NodeHandle> nh_;
43  const std::string topic_name_;
44  const std::string topic_type_;
45  QColor color_ = Qt::GlobalColor::black;
46  unsigned thickness_ = 1;
47  bool displayed_ = true;
48  bool data_update_ = true;
51  QVector<double> topic_data_;
52  QVector<double> topic_time_;
53  QVector<double> getTopicData();
54  QVector<double> getTopicTime();
55  void startRefreshData();
56  void stopRefreshData();
57  void clearData();
58 
59 Q_SIGNALS:
60  void vectorUpdated(std::string topic_name);
61  void displayMessageBox(const QString,
62  const QString,
63  const QString,
64  const QMessageBox::Icon);
65 
66 protected Q_SLOTS:
67  void displayMessageBoxHandler(const QString title,
68  const QString text,
69  const QString info = "",
70  const QMessageBox::Icon icon = QMessageBox::Icon::Information);
71 
72 private:
75  std::mutex data_mutex_;
76  void boolCallback(const std_msgs::BoolConstPtr &msg);
77  void durationCallback(const std_msgs::DurationConstPtr &msg);
78  void float32Callback(const std_msgs::Float32ConstPtr &msg);
79  void float64Callback(const std_msgs::Float64ConstPtr &msg);
80  void int8Callback(const std_msgs::Int8ConstPtr &msg);
81  void int16Callback(const std_msgs::Int16ConstPtr &msg);
82  void int32Callback(const std_msgs::Int32ConstPtr &msg);
83  void int64Callback(const std_msgs::Int64ConstPtr &msg);
84  void timeCallback(const std_msgs::TimeConstPtr &msg);
85  void uint8Callback(const std_msgs::UInt8ConstPtr &msg);
86  void uint16Callback(const std_msgs::UInt16ConstPtr &msg);
87  void uint32Callback(const std_msgs::UInt32ConstPtr &msg);
88  void uint64Callback(const std_msgs::UInt64ConstPtr &msg);
89  void pushData(const double Data, const ros::Time now);
90 };
91 
92 }
93 
94 #endif
void int16Callback(const std_msgs::Int16ConstPtr &msg)
Definition: topic_data.cpp:128
void uint32Callback(const std_msgs::UInt32ConstPtr &msg)
Definition: topic_data.cpp:176
void durationCallback(const std_msgs::DurationConstPtr &msg)
Definition: topic_data.cpp:96
QCPScatterStyle::ScatterShape scatter_shape_
Definition: topic_data.hpp:50
void uint16Callback(const std_msgs::UInt16ConstPtr &msg)
Definition: topic_data.cpp:168
std::shared_ptr< ros::NodeHandle > nh_
Definition: topic_data.hpp:42
QCPGraph::LineStyle line_style_
Definition: topic_data.hpp:49
QVector< double > topic_time_
Definition: topic_data.hpp:52
{ssCross.png} a cross
Definition: qcustomplot.h:2328
void vectorUpdated(std::string topic_name)
QVector< double > getTopicData()
Definition: topic_data.cpp:192
void uint8Callback(const std_msgs::UInt8ConstPtr &msg)
Definition: topic_data.cpp:160
TopicData(std::string topic_name, std::string topic_type, std::shared_ptr< ros::NodeHandle >, QObject *parent=nullptr)
Definition: topic_data.cpp:6
void pushData(const double Data, const ros::Time now)
Definition: topic_data.cpp:70
const std::string topic_name_
Definition: topic_data.hpp:43
QVector< double > getTopicTime()
Definition: topic_data.cpp:198
void timeCallback(const std_msgs::TimeConstPtr &msg)
Definition: topic_data.cpp:152
void float32Callback(const std_msgs::Float32ConstPtr &msg)
Definition: topic_data.cpp:104
QVector< double > topic_data_
Definition: topic_data.hpp:51
void boolCallback(const std_msgs::BoolConstPtr &msg)
Definition: topic_data.cpp:88
const std::string topic_type_
Definition: topic_data.hpp:44
void float64Callback(const std_msgs::Float64ConstPtr &msg)
Definition: topic_data.cpp:112
void int8Callback(const std_msgs::Int8ConstPtr &msg)
Definition: topic_data.cpp:120
void uint64Callback(const std_msgs::UInt64ConstPtr &msg)
Definition: topic_data.cpp:184
void displayMessageBoxHandler(const QString title, const QString text, const QString info="", const QMessageBox::Icon icon=QMessageBox::Icon::Information)
Definition: topic_data.cpp:204
void int64Callback(const std_msgs::Int64ConstPtr &msg)
Definition: topic_data.cpp:144
data points are connected by a straight line
Definition: qcustomplot.h:5181
void displayMessageBox(const QString, const QString, const QString, const QMessageBox::Icon)
void int32Callback(const std_msgs::Int32ConstPtr &msg)
Definition: topic_data.cpp:136


graph_rviz_plugin
Author(s): Édouard Pronier, Victor Lamoine - Institut Maupertuis
autogenerated on Mon Feb 28 2022 22:27:30