histogram_panel.hpp
Go to the documentation of this file.
1 #ifndef GRAPH_RVIZ_PLUGIN_HISTOGRAM_PANEL_HPP
2 #define GRAPH_RVIZ_PLUGIN_HISTOGRAM_PANEL_HPP
3 
4 #include <atomic>
5 #include <cv_bridge/cv_bridge.h>
8 #include <mutex>
9 #include <ros/ros.h>
10 #include <ros/service.h>
11 #include <rviz/panel.h>
12 #include <sensor_msgs/Image.h>
13 
14 #include <QComboBox>
15 #include <QMessageBox>
16 #include <QPushButton>
17 #include <QTimer>
18 #include <QVBoxLayout>
19 
20 namespace graph_rviz_plugin
21 {
22 
24 {
25 Q_OBJECT
26 
27 public:
28  HistogramPanel(QWidget *parent = nullptr);
29  virtual ~HistogramPanel();
30 
31 Q_SIGNALS:
32  void subscribeToTopic(const QString);
33  void enable(const bool);
34  void displayMessageBox(const QString,
35  const QString,
36  const QString,
37  const QMessageBox::Icon);
38 
39 protected Q_SLOTS:
40  void displayMessageBoxHandler(const QString title,
41  const QString text,
42  const QString info = "",
43  const QMessageBox::Icon icon = QMessageBox::Icon::Information);
44  virtual void load(const rviz::Config &config);
45  virtual void save(rviz::Config config) const;
46  void updateChartSlot();
47  void topicSelectionSlot();
48  void subscribeToTopicSlot(const QString topic);
49 
50 private:
51  void imageCallback(const sensor_msgs::ImageConstPtr &msg);
52 
53  std::shared_ptr<ros::NodeHandle> nh_;
55 
56  std::atomic<bool> updating_;
57  std::mutex data_ticks_mutex_;
58 
59  int16_t bins_value_;
60  bool grayscale_ = true; // true <=> grayscale; false <=> color images
62 
63  QString topic_;
64  QVector<double> ticks_;
65  QVector<double> data_; // Grayscale channel histogram data
66  QVector<double> blue_channel_data_; // Blue channel histogram data
67  QVector<double> green_channel_data_; // Green channel histogram data
68  QVector<double> red_channel_data_; // Red channel histogram data
69 
70  QPushButton *start_stop_;
72  QComboBox *bins_selection_;
74 
80 
81 };
82 
83 }
84 
85 #endif
std::shared_ptr< ros::NodeHandle > nh_
void subscribeToTopicSlot(const QString topic)
virtual void save(rviz::Config config) const
config
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
The central class of the library. This is the QWidget which displays the plot and interacts with the ...
Definition: qcustomplot.h:3590
void displayMessageBox(const QString, const QString, const QString, const QMessageBox::Icon)
void subscribeToTopic(const QString)
HistogramPanel(QWidget *parent=nullptr)
A plottable representing a bar chart in a plot.
Definition: qcustomplot.h:5482
void displayMessageBoxHandler(const QString title, const QString text, const QString info="", const QMessageBox::Icon icon=QMessageBox::Icon::Information)
virtual void load(const rviz::Config &config)


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