Skip to content

Commit 5977465

Browse files
feat(trajectory_kinematics_panel): trajectory_kinematics_panel upgrade
Signed-off-by: YuxuanLiuTier4Desktop <619684051@qq.com>
1 parent 700c544 commit 5977465

5 files changed

Lines changed: 93 additions & 156 deletions

File tree

common/autoware_trajectory_kinematics_rviz_plugin/src/kinematics_types.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,9 @@ struct TrajectorySeriesData
4343
std::string key;
4444
std::string label;
4545
std::vector<SeriesPoint> points;
46+
/// True once actual trajectory data has been received; false for placeholder entries
47+
/// that exist only because the topic was added but no message has arrived yet.
48+
bool has_received_data{false};
4649
};
4750

4851
/// @brief Selects which scalar is read from SeriesPoint for an axis or tooltip.

common/autoware_trajectory_kinematics_rviz_plugin/src/trajectory_kinematics_panel.cpp

Lines changed: 60 additions & 134 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "ui_font.hpp"
1919

2020
#include <QAbstractItemView>
21+
#include <QBrush>
2122
#include <QColor>
2223
#include <QHBoxLayout>
2324
#include <QHideEvent>
@@ -55,9 +56,6 @@ constexpr char kScoredType[] = "autoware_internal_planning_msgs/msg/ScoredCandid
5556
/// Shown when the graph has no matching topics (not a valid subscription target).
5657
const QString kEmptyTopicPlaceholder = QStringLiteral("(No matching topics — press Refresh)");
5758

58-
/// Interval for refreshing the ROS graph topic list (ms).
59-
constexpr int kTopicPollIntervalMs = 4000;
60-
6159
/// Debounce window for merging high-rate `dataUpdated` → panel refresh (ms).
6260
constexpr int kPlotRefreshCoalesceMs = 50;
6361

@@ -87,6 +85,33 @@ QIcon makeTrajectoryColorIcon(const QColor & c)
8785
return QIcon(pm);
8886
}
8987

88+
QIcon makeRefreshIcon()
89+
{
90+
constexpr int d = 20;
91+
QPixmap pm(d, d);
92+
pm.fill(Qt::transparent);
93+
QPainter painter(&pm);
94+
painter.setRenderHint(QPainter::Antialiasing, true);
95+
painter.setPen(QPen(Qt::white, 2.0, Qt::SolidLine, Qt::RoundCap));
96+
97+
const QPointF center(d / 2.0, d / 2.0);
98+
constexpr double radius = 6.5;
99+
100+
// Arc: from ~1 o'clock counterclockwise around to ~12 o'clock
101+
QPainterPath arc_path;
102+
arc_path.moveTo(center + QPointF(0, -radius));
103+
arc_path.arcTo(
104+
QRectF(center.x() - radius, center.y() - radius, radius * 2, radius * 2), 90.0, -300.0);
105+
painter.drawPath(arc_path);
106+
107+
// Arrowhead at the top of the arc
108+
painter.drawLine(QPointF(0, -radius + 1.5), QPointF(2.5, -radius - 2.0));
109+
painter.drawLine(QPointF(0, -radius + 1.5), QPointF(-2.5, -radius - 2.0));
110+
111+
painter.end();
112+
return QIcon(pm);
113+
}
114+
90115
QColor colorForSeriesListIndex(int index_in_all_series)
91116
{
92117
return kColorCycle[index_in_all_series % kColorCycleCount];
@@ -125,10 +150,6 @@ QString panelStyleSheet(const style::MaterialColors & c)
125150
" background-color: %3; color: %2; border: 1px solid %4; border-radius: 6px;"
126151
" padding: 5px 10px; font-weight: 600;"
127152
"}"
128-
"QWidget#TkmPanelRoot QDoubleSpinBox {"
129-
" background-color: %3; color: %2; border: 1px solid %4; border-radius: 6px;"
130-
" padding: 3px 6px; min-height: 22px; font-weight: 600;"
131-
"}"
132153
"QWidget#TkmPanelRoot QCheckBox { color: %2; font-weight: 600; spacing: 6px; }")
133154
.arg(QString::fromStdString(c.background))
134155
.arg(QString::fromStdString(c.on_surface))
@@ -161,30 +182,31 @@ TrajectoryKinematicsPanel::TrajectoryKinematicsPanel(QWidget * parent) : rviz_co
161182
row->addWidget(new QLabel(QStringLiteral("Topic:")));
162183
topic_combo_ = new QComboBox();
163184
topic_combo_->setEditable(false);
164-
topic_combo_->setMinimumWidth(260);
185+
topic_combo_->setMinimumWidth(125);
165186
topic_combo_->setMaxVisibleItems(18);
166187
topic_combo_->setSizeAdjustPolicy(QComboBox::AdjustToMinimumContentsLengthWithIcon);
167188
topic_combo_->setMinimumContentsLength(28);
168189
topic_combo_->setToolTip(QStringLiteral(
169-
"Open the list and click a topic. Use Other topic below to type a name not "
190+
"Open the list and click a topic. Use \"Other topic\" below to type a name not "
170191
"listed."));
171192
row->addWidget(topic_combo_, 1);
172193
kind_combo_ = new QComboBox();
173194
kind_combo_->addItem(
174195
QStringLiteral("Trajectory"), static_cast<int>(TopicMessageKind::Trajectory));
175196
kind_combo_->addItem(
176-
QStringLiteral("ScoredCandidateTrajectories"),
197+
QStringLiteral("CandidateTrajectories"),
177198
static_cast<int>(TopicMessageKind::ScoredCandidateTrajectories));
178199
row->addWidget(kind_combo_);
179-
refresh_topics_button_ = new QPushButton(QStringLiteral("Refresh topics"));
200+
refresh_topics_button_ = new QPushButton(makeRefreshIcon(), QString());
201+
refresh_topics_button_->setMaximumWidth(36);
180202
refresh_topics_button_->setToolTip(
181203
QStringLiteral("Reload topic list from the ROS graph (filtered by message type)"));
182204
row->addWidget(refresh_topics_button_);
183205
add_topic_button_ = new QPushButton(QStringLiteral("Add"));
184206
remove_topic_button_ = new QPushButton(QStringLiteral("Remove"));
185-
remove_topic_button_->setToolTip(QStringLiteral(
186-
"Select one or more trajectories below, then remove their ROS topic "
187-
"subscription(s)."));
207+
remove_topic_button_->setToolTip(
208+
QStringLiteral("Select one or more trajectories below, then remove their ROS topic "
209+
"subscription(s)."));
188210
row->addWidget(add_topic_button_);
189211
row->addWidget(remove_topic_button_);
190212
root->addLayout(row);
@@ -197,9 +219,9 @@ TrajectoryKinematicsPanel::TrajectoryKinematicsPanel(QWidget * parent) : rviz_co
197219
manual_topic_edit_->setObjectName(QStringLiteral("TkmManualTopic"));
198220
manual_topic_edit_->setPlaceholderText(
199221
QStringLiteral("Optional: type a full topic name if it is not in the list above"));
200-
manual_topic_edit_->setToolTip(QStringLiteral(
201-
"If set, Add uses this text instead of the dropdown (for topics not yet on "
202-
"the graph)."));
222+
manual_topic_edit_->setToolTip(
223+
QStringLiteral("If set, Add uses this text instead of the dropdown (for topics not yet on "
224+
"the graph)."));
203225
row->addWidget(manual_topic_edit_, 1);
204226
root->addLayout(row);
205227
}
@@ -210,11 +232,12 @@ TrajectoryKinematicsPanel::TrajectoryKinematicsPanel(QWidget * parent) : rviz_co
210232
root->addWidget(series_label);
211233
series_list_ = new QListWidget();
212234
series_list_->setSelectionMode(QAbstractItemView::ExtendedSelection);
213-
series_list_->setToolTip(QStringLiteral(
214-
"Swatch = plot line color. Check rows to plot. Select row(s) and use Remove "
215-
"to drop that topic subscription."));
235+
series_list_->setToolTip(
236+
QStringLiteral("Swatch = plot line color. Check rows to plot. Select row(s) and use Remove "
237+
"to drop that topic subscription."));
216238
series_list_->setIconSize(QSize(20, 20));
217-
series_list_->setMinimumHeight(160);
239+
series_list_->setMinimumHeight(60);
240+
series_list_->setMaximumHeight(90);
218241
root->addWidget(series_list_);
219242
}
220243

@@ -229,52 +252,6 @@ TrajectoryKinematicsPanel::TrajectoryKinematicsPanel(QWidget * parent) : rviz_co
229252
root->addLayout(row);
230253
}
231254

232-
{
233-
auto * row = new QHBoxLayout();
234-
fix_x_range_ = new QCheckBox(QStringLiteral("Fix X range"));
235-
plot_x_min_spin_ = new QDoubleSpinBox();
236-
plot_x_max_spin_ = new QDoubleSpinBox();
237-
for (auto * sp : {plot_x_min_spin_, plot_x_max_spin_}) {
238-
sp->setDecimals(4);
239-
sp->setRange(-1e9, 1e9);
240-
sp->setMaximumWidth(130);
241-
}
242-
plot_x_min_spin_->setValue(0.0);
243-
plot_x_max_spin_->setValue(20.0);
244-
plot_x_min_spin_->setToolTip(QStringLiteral("Used when “Fix X range” is checked"));
245-
plot_x_max_spin_->setToolTip(QStringLiteral("Must be greater than min"));
246-
row->addWidget(fix_x_range_);
247-
row->addWidget(new QLabel(QStringLiteral("min")));
248-
row->addWidget(plot_x_min_spin_);
249-
row->addWidget(new QLabel(QStringLiteral("max")));
250-
row->addWidget(plot_x_max_spin_);
251-
row->addStretch();
252-
root->addLayout(row);
253-
}
254-
255-
{
256-
auto * row = new QHBoxLayout();
257-
fix_y_range_ = new QCheckBox(QStringLiteral("Fix Y range"));
258-
plot_y_min_spin_ = new QDoubleSpinBox();
259-
plot_y_max_spin_ = new QDoubleSpinBox();
260-
for (auto * sp : {plot_y_min_spin_, plot_y_max_spin_}) {
261-
sp->setDecimals(4);
262-
sp->setRange(-1e9, 1e9);
263-
sp->setMaximumWidth(130);
264-
}
265-
plot_y_min_spin_->setValue(-5.0);
266-
plot_y_max_spin_->setValue(15.0);
267-
plot_y_min_spin_->setToolTip(QStringLiteral("Used when “Fix Y range” is checked"));
268-
plot_y_max_spin_->setToolTip(QStringLiteral("Must be greater than min"));
269-
row->addWidget(fix_y_range_);
270-
row->addWidget(new QLabel(QStringLiteral("min")));
271-
row->addWidget(plot_y_min_spin_);
272-
row->addWidget(new QLabel(QStringLiteral("max")));
273-
row->addWidget(plot_y_max_spin_);
274-
row->addStretch();
275-
root->addLayout(row);
276-
}
277-
278255
{
279256
auto * row = new QHBoxLayout();
280257
row->addWidget(new QLabel(QStringLiteral("End v:")));
@@ -297,9 +274,6 @@ TrajectoryKinematicsPanel::TrajectoryKinematicsPanel(QWidget * parent) : rviz_co
297274
outer->addWidget(panel_root_);
298275
setLayout(outer);
299276

300-
topic_poll_timer_ = new QTimer(this);
301-
topic_poll_timer_->setInterval(kTopicPollIntervalMs);
302-
303277
plot_refresh_coalesce_timer_ = new QTimer(this);
304278
plot_refresh_coalesce_timer_->setSingleShot(true);
305279
plot_refresh_coalesce_timer_->setInterval(kPlotRefreshCoalesceMs);
@@ -316,7 +290,6 @@ TrajectoryKinematicsPanel::TrajectoryKinematicsPanel(QWidget * parent) : rviz_co
316290
connect(
317291
kind_combo_, qOverload<int>(&QComboBox::currentIndexChanged), this,
318292
&TrajectoryKinematicsPanel::refreshTopicList);
319-
connect(topic_poll_timer_, &QTimer::timeout, this, &TrajectoryKinematicsPanel::refreshTopicList);
320293
connect(
321294
plot_refresh_coalesce_timer_, &QTimer::timeout, this,
322295
&TrajectoryKinematicsPanel::processDataUpdated);
@@ -328,20 +301,6 @@ TrajectoryKinematicsPanel::TrajectoryKinematicsPanel(QWidget * parent) : rviz_co
328301
connect(
329302
y_axis_combo_, qOverload<int>(&QComboBox::currentIndexChanged), this,
330303
&TrajectoryKinematicsPanel::onAxisChanged);
331-
connect(fix_x_range_, &QCheckBox::toggled, this, &TrajectoryKinematicsPanel::refreshPlot);
332-
connect(fix_y_range_, &QCheckBox::toggled, this, &TrajectoryKinematicsPanel::refreshPlot);
333-
connect(
334-
plot_x_min_spin_, qOverload<double>(&QDoubleSpinBox::valueChanged), this,
335-
&TrajectoryKinematicsPanel::refreshPlot);
336-
connect(
337-
plot_x_max_spin_, qOverload<double>(&QDoubleSpinBox::valueChanged), this,
338-
&TrajectoryKinematicsPanel::refreshPlot);
339-
connect(
340-
plot_y_min_spin_, qOverload<double>(&QDoubleSpinBox::valueChanged), this,
341-
&TrajectoryKinematicsPanel::refreshPlot);
342-
connect(
343-
plot_y_max_spin_, qOverload<double>(&QDoubleSpinBox::valueChanged), this,
344-
&TrajectoryKinematicsPanel::refreshPlot);
345304
}
346305

347306
void TrajectoryKinematicsPanel::applyPanelStyle()
@@ -352,16 +311,10 @@ void TrajectoryKinematicsPanel::applyPanelStyle()
352311
panel_root_->setStyleSheet(panelStyleSheet(style::default_colors));
353312
}
354313

355-
PlotAxisRangeOptions TrajectoryKinematicsPanel::readPlotRangeOptions() const
314+
PlotAxisRangeOptions readPlotRangeOptionsDefault()
356315
{
357-
PlotAxisRangeOptions o;
358-
o.lock_x = fix_x_range_->isChecked();
359-
o.x_min = plot_x_min_spin_->value();
360-
o.x_max = plot_x_max_spin_->value();
361-
o.lock_y = fix_y_range_->isChecked();
362-
o.y_min = plot_y_min_spin_->value();
363-
o.y_max = plot_y_max_spin_->value();
364-
return o;
316+
// Always use dynamic range; lock flags are off and min/max values are ignored.
317+
return PlotAxisRangeOptions{};
365318
}
366319

367320
void TrajectoryKinematicsPanel::populateAxisCombos()
@@ -568,13 +521,13 @@ void TrajectoryKinematicsPanel::rebuildSeriesListWidget()
568521
return;
569522
}
570523
const auto all = series_manager_->allSeries();
571-
std::vector<std::pair<std::string, std::string>> current_sig;
524+
std::vector<std::tuple<std::string, std::string, bool>> current_sig;
572525
current_sig.reserve(all.size());
573526
for (const auto & s : all) {
574-
current_sig.emplace_back(TrajectorySeriesManager::seriesId(s), s.label);
527+
current_sig.emplace_back(TrajectorySeriesManager::seriesId(s), s.label, s.has_received_data);
575528
}
576-
// Skip QListWidget rebuild when only point values changed but ids/labels are unchanged (keeps
577-
// selection/focus stable).
529+
// Skip QListWidget rebuild when only point values changed but ids/labels/data-state are unchanged
530+
// (keeps selection/focus stable).
578531
if (current_sig == last_series_list_signature_) {
579532
return;
580533
}
@@ -585,7 +538,14 @@ void TrajectoryKinematicsPanel::rebuildSeriesListWidget()
585538
for (size_t ai = 0; ai < all.size(); ++ai) {
586539
const auto & s = all[ai];
587540
const std::string id = TrajectorySeriesManager::seriesId(s);
588-
auto * item = new QListWidgetItem(QString::fromStdString(s.label));
541+
QString display_label = QString::fromStdString(s.label);
542+
if (!s.has_received_data) {
543+
display_label += QStringLiteral(" (waiting...)");
544+
}
545+
auto * item = new QListWidgetItem(display_label);
546+
if (!s.has_received_data) {
547+
item->setForeground(QBrush(Qt::gray));
548+
}
589549
item->setData(static_cast<int>(SeriesListItemRole::kSeriesId), QString::fromStdString(id));
590550
item->setData(static_cast<int>(SeriesListItemRole::kAllSeriesIndex), static_cast<int>(ai));
591551
item->setData(
@@ -644,7 +604,7 @@ void TrajectoryKinematicsPanel::refreshPlot()
644604
selected.push_back(all[static_cast<size_t>(ai)]);
645605
colors.push_back(colorForSeriesListIndex(ai));
646606
}
647-
plot_widget_->updatePlot(selected, colors, x_axis, y_axis, readPlotRangeOptions());
607+
plot_widget_->updatePlot(selected, colors, x_axis, y_axis, readPlotRangeOptionsDefault());
648608
updateSummary(selected);
649609
}
650610

@@ -720,12 +680,6 @@ void TrajectoryKinematicsPanel::save(rviz_common::Config config) const
720680
}
721681
checked_ids.sort();
722682
config.mapSetValue("checked_series", checked_ids.join(QStringLiteral(",")));
723-
config.mapSetValue("plot_lock_x", fix_x_range_->isChecked() ? 1 : 0);
724-
config.mapSetValue("plot_lock_y", fix_y_range_->isChecked() ? 1 : 0);
725-
config.mapSetValue("plot_x_min", QString::number(plot_x_min_spin_->value(), 'g', 12));
726-
config.mapSetValue("plot_x_max", QString::number(plot_x_max_spin_->value(), 'g', 12));
727-
config.mapSetValue("plot_y_min", QString::number(plot_y_min_spin_->value(), 'g', 12));
728-
config.mapSetValue("plot_y_max", QString::number(plot_y_max_spin_->value(), 'g', 12));
729683
}
730684

731685
void TrajectoryKinematicsPanel::load(const rviz_common::Config & config)
@@ -762,44 +716,16 @@ void TrajectoryKinematicsPanel::load(const rviz_common::Config & config)
762716
}
763717
}
764718

765-
int plot_lock_x = 0;
766-
int plot_lock_y = 0;
767-
if (config.mapGetInt("plot_lock_x", &plot_lock_x)) {
768-
fix_x_range_->setChecked(plot_lock_x != 0);
769-
}
770-
if (config.mapGetInt("plot_lock_y", &plot_lock_y)) {
771-
fix_y_range_->setChecked(plot_lock_y != 0);
772-
}
773-
QString q_string;
774-
if (config.mapGetString("plot_x_min", &q_string)) {
775-
plot_x_min_spin_->setValue(q_string.toDouble());
776-
}
777-
if (config.mapGetString("plot_x_max", &q_string)) {
778-
plot_x_max_spin_->setValue(q_string.toDouble());
779-
}
780-
if (config.mapGetString("plot_y_min", &q_string)) {
781-
plot_y_min_spin_->setValue(q_string.toDouble());
782-
}
783-
if (config.mapGetString("plot_y_max", &q_string)) {
784-
plot_y_max_spin_->setValue(q_string.toDouble());
785-
}
786-
787719
applyTopicConfigsToManager();
788720
}
789721

790722
void TrajectoryKinematicsPanel::showEvent(QShowEvent * event)
791723
{
792724
rviz_common::Panel::showEvent(event);
793-
if (topic_poll_timer_) {
794-
topic_poll_timer_->start();
795-
}
796725
}
797726

798727
void TrajectoryKinematicsPanel::hideEvent(QHideEvent * event)
799728
{
800-
if (topic_poll_timer_) {
801-
topic_poll_timer_->stop();
802-
}
803729
rviz_common::Panel::hideEvent(event);
804730
}
805731

0 commit comments

Comments
 (0)