1 #ifndef GRAPH_RVIZ_PLUGIN_HISTOGRAM_PANEL_HPP 2 #define GRAPH_RVIZ_PLUGIN_HISTOGRAM_PANEL_HPP 12 #include <sensor_msgs/Image.h> 15 #include <QMessageBox> 16 #include <QPushButton> 18 #include <QVBoxLayout> 37 const QMessageBox::Icon);
42 const QString info =
"",
43 const QMessageBox::Icon icon = QMessageBox::Icon::Information);
53 std::shared_ptr<ros::NodeHandle>
nh_;
std::shared_ptr< ros::NodeHandle > nh_
void subscribeToTopicSlot(const QString topic)
QVector< double > blue_channel_data_
virtual void save(rviz::Config config) const
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
QVector< double > red_channel_data_
std::mutex data_ticks_mutex_
QCustomPlot * custom_plot_
The central class of the library. This is the QWidget which displays the plot and interacts with the ...
QComboBox * graph_refresh_frequency_
QVector< double > green_channel_data_
QComboBox * bins_selection_
void displayMessageBox(const QString, const QString, const QString, const QMessageBox::Icon)
double histogram_max_counter_
void subscribeToTopic(const QString)
HistogramPanel(QWidget *parent=nullptr)
virtual ~HistogramPanel()
A plottable representing a bar chart in a plot.
std::atomic< bool > updating_
void displayMessageBoxHandler(const QString title, const QString text, const QString info="", const QMessageBox::Icon icon=QMessageBox::Icon::Information)
QPushButton * start_stop_
QTimer * graph_refresh_timer_
void topicSelectionSlot()
virtual void load(const rviz::Config &config)