Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(factors_panel, tier4_state_rviz_plugin): check abrupt deceleration #1674

Merged
merged 2 commits into from
Dec 2, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions common/tier4_state_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>libqt5-core</depend>
<depend>libqt5-gui</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,18 +17,19 @@
#ifndef VELOCITY_STEERING_FACTORS_PANEL_HPP_
#define VELOCITY_STEERING_FACTORS_PANEL_HPP_

#include <QDoubleSpinBox>
#include <QGroupBox>
#include <QLabel>
#include <QLayout>
#include <QPushButton>
#include <QSpinBox>
#include <QTableWidget>
#include <rclcpp/rclcpp.hpp>
#include <rviz_common/panel.hpp>

#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
#include <autoware_adapi_v1_msgs/msg/steering_factor_array.hpp>
#include <autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp>
#include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

#include <memory>

Expand All @@ -49,6 +50,11 @@ class VelocitySteeringFactorsPanel : public rviz_common::Panel
void onInitialize() override;

protected:
static constexpr double JERK_DEFAULT = 1.0;
static constexpr double DECEL_LIMIT_DEFAULT = 1.0;

static constexpr QColor COLOR_FREAK_PINK = {255, 0, 108};

// Layout
QGroupBox * makeVelocityFactorsGroup();
QGroupBox * makeSteeringFactorsGroup();
Expand All @@ -58,7 +64,14 @@ class VelocitySteeringFactorsPanel : public rviz_common::Panel
// Planning
QTableWidget * velocity_factors_table_{nullptr};
QTableWidget * steering_factors_table_{nullptr};
QDoubleSpinBox * jerk_input_{nullptr};
QDoubleSpinBox * decel_limit_input_{nullptr};

nav_msgs::msg::Odometry::ConstSharedPtr kinematic_state_;
geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr acceleration_;

rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_kinematic_state_;
rclcpp::Subscription<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr sub_acceleration_;
rclcpp::Subscription<VelocityFactorArray>::SharedPtr sub_velocity_factors_;
rclcpp::Subscription<SteeringFactorArray>::SharedPtr sub_steering_factors_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <QHeaderView>
#include <QString>
#include <QVBoxLayout>
#include <autoware/motion_utils/distance/distance.hpp>
#include <rviz_common/display_context.hpp>

#include <memory>
Expand All @@ -46,15 +47,36 @@ QGroupBox * VelocitySteeringFactorsPanel::makeVelocityFactorsGroup()
auto vertical_header = new QHeaderView(Qt::Vertical);
vertical_header->hide();
auto horizontal_header = new QHeaderView(Qt::Horizontal);
horizontal_header->setSectionResizeMode(QHeaderView::Stretch);
horizontal_header->setSectionResizeMode(QHeaderView::ResizeToContents);
horizontal_header->setStretchLastSection(true);

auto header_labels = QStringList({"Type", "Status", "Distance [m]", "Detail"});
velocity_factors_table_ = new QTableWidget();
velocity_factors_table_->setColumnCount(header_labels.size());
velocity_factors_table_->setHorizontalHeaderLabels(header_labels);
velocity_factors_table_->setVerticalHeader(vertical_header);
velocity_factors_table_->setHorizontalHeader(horizontal_header);
grid->addWidget(velocity_factors_table_, 0, 0);
grid->addWidget(velocity_factors_table_, 0, 0, 4, 1);

auto * jerk_label = new QLabel("Jerk");
grid->addWidget(jerk_label, 0, 1);

jerk_input_ = new QDoubleSpinBox;
jerk_input_->setMinimum(0.0);
jerk_input_->setValue(JERK_DEFAULT);
jerk_input_->setSingleStep(0.1);
jerk_input_->setSuffix(" [m/s\u00B3]");
grid->addWidget(jerk_input_, 1, 1);

auto * decel_limit_label = new QLabel("Decel limit");
grid->addWidget(decel_limit_label, 2, 1);

decel_limit_input_ = new QDoubleSpinBox;
decel_limit_input_->setMinimum(0.0);
decel_limit_input_->setValue(DECEL_LIMIT_DEFAULT);
decel_limit_input_->setSingleStep(0.1);
decel_limit_input_->setSuffix(" [m/s\u00B2]");
grid->addWidget(decel_limit_input_, 3, 1);

group->setLayout(grid);
return group;
Expand Down Expand Up @@ -90,6 +112,17 @@ void VelocitySteeringFactorsPanel::onInitialize()
raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();

// Planning
sub_kinematic_state_ = raw_node_->create_subscription<nav_msgs::msg::Odometry>(
"/localization/kinematic_state", 10,
[this](const nav_msgs::msg::Odometry::ConstSharedPtr msg) { kinematic_state_ = msg; });

sub_acceleration_ =
raw_node_->create_subscription<geometry_msgs::msg::AccelWithCovarianceStamped>(
"/localization/acceleration", 10,
[this](const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg) {
acceleration_ = msg;
});

sub_velocity_factors_ = raw_node_->create_subscription<VelocityFactorArray>(
"/api/planning/velocity_factors", 10,
std::bind(&VelocitySteeringFactorsPanel::onVelocityFactors, this, _1));
Expand All @@ -104,8 +137,15 @@ void VelocitySteeringFactorsPanel::onVelocityFactors(const VelocityFactorArray::
velocity_factors_table_->clearContents();
velocity_factors_table_->setRowCount(msg->factors.size());

for (std::size_t i = 0; i < msg->factors.size(); i++) {
const auto & e = msg->factors.at(i);
auto sorted = *msg;

// sort by distance to the decel/stop point.
std::sort(sorted.factors.begin(), sorted.factors.end(), [](const auto & a, const auto & b) {
return a.distance < b.distance;
});

for (std::size_t i = 0; i < sorted.factors.size(); i++) {
const auto & e = sorted.factors.at(i);

// behavior
{
Expand Down Expand Up @@ -148,6 +188,26 @@ void VelocitySteeringFactorsPanel::onVelocityFactors(const VelocityFactorArray::
label->setAlignment(Qt::AlignCenter);
velocity_factors_table_->setCellWidget(i, 3, label);
}

const auto row_background = [&]() -> QBrush {
if (!kinematic_state_ || !acceleration_) {
return {};
}
const auto & current_vel = kinematic_state_->twist.twist.linear.x;
const auto & current_acc = acceleration_->accel.accel.linear.x;
const auto acc_min = -decel_limit_input_->value();
const auto jerk_acc = jerk_input_->value();
const auto decel_dist = autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints(
current_vel, 0., current_acc, acc_min, jerk_acc, -jerk_acc);
if (decel_dist > e.distance && e.distance >= 0 && e.status == VelocityFactor::APPROACHING) {
return COLOR_FREAK_PINK;
}
return {};
}();
for (int j = 0; j < velocity_factors_table_->columnCount(); j++) {
velocity_factors_table_->setItem(i, j, new QTableWidgetItem);
velocity_factors_table_->item(i, j)->setBackground(row_background);
}
}
velocity_factors_table_->update();
}
Expand All @@ -157,8 +217,15 @@ void VelocitySteeringFactorsPanel::onSteeringFactors(const SteeringFactorArray::
steering_factors_table_->clearContents();
steering_factors_table_->setRowCount(msg->factors.size());

for (std::size_t i = 0; i < msg->factors.size(); i++) {
const auto & e = msg->factors.at(i);
auto sorted = *msg;

// sort by distance to the point where it starts moving the steering.
std::sort(sorted.factors.begin(), sorted.factors.end(), [](const auto & a, const auto & b) {
return a.distance.front() < b.distance.front();
});

for (std::size_t i = 0; i < sorted.factors.size(); i++) {
const auto & e = sorted.factors.at(i);

// behavior
{
Expand Down
Loading