@@ -30,6 +30,12 @@ MetricsVisualizePanel::MetricsVisualizePanel(QWidget * parent)
30
30
: rviz_common::Panel(parent), grid_(new QGridLayout())
31
31
{
32
32
setLayout (grid_);
33
+ topic_selector_ = new QComboBox ();
34
+ for (const auto & topic : topics_) {
35
+ topic_selector_->addItem (QString::fromStdString (topic));
36
+ }
37
+ grid_->addWidget (topic_selector_, 0 , 0 , 1 , -1 );
38
+ connect (topic_selector_, SIGNAL (currentIndexChanged (int )), this , SLOT (onTopicChanged ()));
33
39
}
34
40
35
41
void MetricsVisualizePanel::onInitialize ()
@@ -38,14 +44,53 @@ void MetricsVisualizePanel::onInitialize()
38
44
39
45
raw_node_ = this ->getDisplayContext ()->getRosNodeAbstraction ().lock ()->get_raw_node ();
40
46
41
- sub_ = raw_node_->create_subscription <DiagnosticArray>(
42
- " /diagnostic/planning_evaluator/metrics" , rclcpp::QoS{1 },
43
- std::bind (&MetricsVisualizePanel::onMetrics, this , _1));
47
+ for (const auto & topic_name : topics_) {
48
+ const auto callback = [this , topic_name](const DiagnosticArray::ConstSharedPtr msg) {
49
+ this ->onMetrics (msg, topic_name);
50
+ };
51
+ const auto subscription =
52
+ raw_node_->create_subscription <DiagnosticArray>(topic_name, rclcpp::QoS{1 }, callback);
53
+ subscriptions_[topic_name] = subscription;
54
+ }
44
55
45
56
const auto period = std::chrono::milliseconds (static_cast <int64_t >(1e3 / 10 ));
46
57
timer_ = raw_node_->create_wall_timer (period, [&]() { onTimer (); });
47
58
}
48
59
60
+ void MetricsVisualizePanel::updateWidgetVisibility (
61
+ const std::string & target_topic, const bool show)
62
+ {
63
+ for (const auto & [topic_name, metric_widgets_pair] : topic_widgets_map_) {
64
+ const bool is_target_topic = (topic_name == target_topic);
65
+ if ((!is_target_topic && show) || (is_target_topic && !show)) {
66
+ continue ;
67
+ }
68
+ for (const auto & [metric, widgets] : metric_widgets_pair) {
69
+ widgets.first ->setVisible (show);
70
+ widgets.second ->setVisible (show);
71
+ }
72
+ }
73
+ }
74
+
75
+ void MetricsVisualizePanel::showCurrentTopicWidgets ()
76
+ {
77
+ const std::string current_topic = topic_selector_->currentText ().toStdString ();
78
+ updateWidgetVisibility (current_topic, true );
79
+ }
80
+
81
+ void MetricsVisualizePanel::hideInactiveTopicWidgets ()
82
+ {
83
+ const std::string current_topic = topic_selector_->currentText ().toStdString ();
84
+ updateWidgetVisibility (current_topic, false );
85
+ }
86
+
87
+ void MetricsVisualizePanel::onTopicChanged ()
88
+ {
89
+ std::lock_guard<std::mutex> message_lock (mutex_);
90
+ hideInactiveTopicWidgets ();
91
+ showCurrentTopicWidgets ();
92
+ }
93
+
49
94
void MetricsVisualizePanel::onTimer ()
50
95
{
51
96
std::lock_guard<std::mutex> message_lock (mutex_);
@@ -56,24 +101,38 @@ void MetricsVisualizePanel::onTimer()
56
101
}
57
102
}
58
103
59
- void MetricsVisualizePanel::onMetrics (const DiagnosticArray::ConstSharedPtr msg)
104
+ void MetricsVisualizePanel::onMetrics (
105
+ const DiagnosticArray::ConstSharedPtr & msg, const std::string & topic_name)
60
106
{
61
107
std::lock_guard<std::mutex> message_lock (mutex_);
62
108
63
109
const auto time = msg->header .stamp .sec + msg->header .stamp .nanosec * 1e-9 ;
64
-
65
110
constexpr size_t GRAPH_COL_SIZE = 5 ;
66
- for (size_t i = 0 ; i < msg->status .size (); ++i) {
67
- const auto & status = msg->status .at (i);
68
111
112
+ for (const auto & status : msg->status ) {
113
+ const size_t num_current_metrics = topic_widgets_map_[topic_name].size ();
69
114
if (metrics_.count (status.name ) == 0 ) {
70
- auto metric = Metric (status);
115
+ const auto metric = Metric (status);
71
116
metrics_.emplace (status.name , metric);
72
- grid_->addWidget (metric.getTable (), i / GRAPH_COL_SIZE * 2 , i % GRAPH_COL_SIZE);
73
- grid_->setRowStretch (i / GRAPH_COL_SIZE * 2 , false );
74
- grid_->addWidget (metric.getChartView (), i / GRAPH_COL_SIZE * 2 + 1 , i % GRAPH_COL_SIZE);
75
- grid_->setRowStretch (i / GRAPH_COL_SIZE * 2 + 1 , true );
76
- grid_->setColumnStretch (i % GRAPH_COL_SIZE, true );
117
+
118
+ // Calculate grid position
119
+ const size_t row = num_current_metrics / GRAPH_COL_SIZE * 2 +
120
+ 1 ; // start from 1 to leave space for the topic selector
121
+ const size_t col = num_current_metrics % GRAPH_COL_SIZE;
122
+
123
+ // Get the widgets from the metric
124
+ const auto tableWidget = metric.getTable ();
125
+ const auto chartViewWidget = metric.getChartView ();
126
+
127
+ // Add the widgets to the grid layout
128
+ grid_->addWidget (tableWidget, row, col);
129
+ grid_->setRowStretch (row, false );
130
+ grid_->addWidget (chartViewWidget, row + 1 , col);
131
+ grid_->setRowStretch (row + 1 , true );
132
+ grid_->setColumnStretch (col, true );
133
+
134
+ // Also add the widgets to the graph_widgets_ vector for easy removal later
135
+ topic_widgets_map_[topic_name][status.name ] = std::make_pair (tableWidget, chartViewWidget);
77
136
}
78
137
79
138
metrics_.at (status.name ).updateData (time , status);
0 commit comments