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(autonomous_emergency_braking): add info marker and override for state #8312

Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
use_pointcloud_data: true
use_predicted_object_data: true
use_object_velocity_calculation: true
check_autoware_state: true
min_generated_path_length: 0.5
imu_prediction_time_horizon: 1.5
imu_prediction_time_interval: 0.1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -260,7 +260,8 @@ class AEB : public rclcpp::Node
this, "/autoware/state"};
// publisher
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pub_obstacle_pointcloud_;
rclcpp::Publisher<MarkerArray>::SharedPtr debug_ego_path_publisher_; // debug
rclcpp::Publisher<MarkerArray>::SharedPtr debug_marker_publisher_;
rclcpp::Publisher<MarkerArray>::SharedPtr info_marker_publisher_;

// timer
rclcpp::TimerBase::SharedPtr timer_;
Expand Down Expand Up @@ -308,6 +309,8 @@ class AEB : public rclcpp::Node

void addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers);

void addVirtualStopWallMarker(MarkerArray & markers);

std::optional<double> calcObjectSpeedFromHistory(
const ObjectData & closest_object, const Path & path, const double current_ego_speed);

Expand Down Expand Up @@ -335,6 +338,7 @@ class AEB : public rclcpp::Node
bool use_pointcloud_data_;
bool use_predicted_object_data_;
bool use_object_velocity_calculation_;
bool check_autoware_state_;
double path_footprint_extra_margin_;
double detection_range_min_height_;
double detection_range_max_height_margin_;
Expand Down
41 changes: 27 additions & 14 deletions control/autoware_autonomous_emergency_braking/src/node.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check notice on line 1 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 5.72 to 5.58, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -125,7 +125,8 @@
{
pub_obstacle_pointcloud_ =
this->create_publisher<sensor_msgs::msg::PointCloud2>("~/debug/obstacle_pointcloud", 1);
debug_ego_path_publisher_ = this->create_publisher<MarkerArray>("~/debug/markers", 1);
debug_marker_publisher_ = this->create_publisher<MarkerArray>("~/debug/markers", 1);
info_marker_publisher_ = this->create_publisher<MarkerArray>("~/info/markers", 1);

Check warning on line 129 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L128-L129

Added lines #L128 - L129 were not covered by tests
}
// Diagnostics
{
Expand All @@ -140,6 +141,7 @@
use_pointcloud_data_ = declare_parameter<bool>("use_pointcloud_data");
use_predicted_object_data_ = declare_parameter<bool>("use_predicted_object_data");
use_object_velocity_calculation_ = declare_parameter<bool>("use_object_velocity_calculation");
check_autoware_state_ = declare_parameter<bool>("check_autoware_state");

Check warning on line 144 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L144

Added line #L144 was not covered by tests
path_footprint_extra_margin_ = declare_parameter<double>("path_footprint_extra_margin");
detection_range_min_height_ = declare_parameter<double>("detection_range_min_height");
detection_range_max_height_margin_ =
Expand Down Expand Up @@ -193,6 +195,7 @@
updateParam<bool>(parameters, "use_predicted_object_data", use_predicted_object_data_);
updateParam<bool>(
parameters, "use_object_velocity_calculation", use_object_velocity_calculation_);
updateParam<bool>(parameters, "check_autoware_state", check_autoware_state_);

Check warning on line 198 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L198

Added line #L198 was not covered by tests
updateParam<double>(parameters, "path_footprint_extra_margin", path_footprint_extra_margin_);
updateParam<double>(parameters, "detection_range_min_height", detection_range_min_height_);
updateParam<double>(
Expand Down Expand Up @@ -363,7 +366,7 @@
}

autoware_state_ = sub_autoware_state_.takeData();
if (!autoware_state_) {
if (check_autoware_state_ && !autoware_state_) {

Check warning on line 369 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

AEB::fetchLatestData increases in cyclomatic complexity from 16 to 17, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
return missing("autoware_state");
}

Expand All @@ -373,6 +376,7 @@
void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
{
MarkerArray debug_markers;
MarkerArray info_markers;
checkCollision(debug_markers);

if (!collision_data_keeper_.checkCollisionExpired()) {
Expand All @@ -386,14 +390,16 @@
if (publish_debug_markers_) {
addCollisionMarker(data, debug_markers);
}
addVirtualStopWallMarker(info_markers);

Check warning on line 393 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L393

Added line #L393 was not covered by tests
} else {
const std::string error_msg = "[AEB]: No Collision";
const auto diag_level = DiagnosticStatus::OK;
stat.summary(diag_level, error_msg);
}

// publish debug markers
debug_ego_path_publisher_->publish(debug_markers);
debug_marker_publisher_->publish(debug_markers);
info_marker_publisher_->publish(info_markers);

Check warning on line 402 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L401-L402

Added lines #L401 - L402 were not covered by tests
}

bool AEB::checkCollision(MarkerArray & debug_markers)
Expand All @@ -406,7 +412,7 @@
}

// if not driving, disable aeb
if (autoware_state_->state != AutowareState::DRIVING) {
if (check_autoware_state_ && autoware_state_->state != AutowareState::DRIVING) {

Check warning on line 415 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

AEB::checkCollision increases in cyclomatic complexity from 18 to 19, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
return false;
}

Expand Down Expand Up @@ -890,20 +896,17 @@
"Object velocity: " + std::to_string(obj.velocity) + " [m/s]\n";
closest_object_velocity_marker_array.text +=
"Object relative velocity to ego: " + std::to_string(obj.velocity - std::abs(ego_velocity)) +
" [m/s]";
" [m/s]\n";
closest_object_velocity_marker_array.text +=
"Object distance to ego: " + std::to_string(obj.distance_to_object) + " [m]\n";

Check warning on line 901 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L901

Added line #L901 was not covered by tests
closest_object_velocity_marker_array.text +=
"RSS distance: " + std::to_string(obj.rss) + " [m]";

Check warning on line 903 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L903

Added line #L903 was not covered by tests
debug_markers.markers.push_back(closest_object_velocity_marker_array);
}
}

void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers)
void AEB::addVirtualStopWallMarker(MarkerArray & markers)

Check warning on line 908 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L908

Added line #L908 was not covered by tests
{
auto point_marker = autoware::universe_utils::createDefaultMarker(
"base_link", data.stamp, "collision_point", 0, Marker::SPHERE,
autoware::universe_utils::createMarkerScale(0.3, 0.3, 0.3),
autoware::universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.3));
point_marker.pose.position = data.position;
debug_markers.markers.push_back(point_marker);

const auto ego_map_pose = std::invoke([this]() -> std::optional<geometry_msgs::msg::Pose> {
geometry_msgs::msg::TransformStamped tf_current_pose;
geometry_msgs::msg::Pose p;
Expand All @@ -928,10 +931,20 @@
ego_map_pose.value(), base_to_front_offset, 0.0, 0.0, 0.0);
const auto virtual_stop_wall = autoware::motion_utils::createStopVirtualWallMarker(
ego_front_pose, "autonomous_emergency_braking", this->now(), 0);
autoware::universe_utils::appendMarkerArray(virtual_stop_wall, &debug_markers);
autoware::universe_utils::appendMarkerArray(virtual_stop_wall, &markers);

Check warning on line 934 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L934

Added line #L934 was not covered by tests
}
}

void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers)

Check warning on line 938 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L938

Added line #L938 was not covered by tests
{
auto point_marker = autoware::universe_utils::createDefaultMarker(
"base_link", data.stamp, "collision_point", 0, Marker::SPHERE,
autoware::universe_utils::createMarkerScale(0.3, 0.3, 0.3),
autoware::universe_utils::createMarkerColor(1.0, 0.0, 0.0, 0.3));
point_marker.pose.position = data.position;
debug_markers.markers.push_back(point_marker);

Check warning on line 945 in control/autoware_autonomous_emergency_braking/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_autonomous_emergency_braking/src/node.cpp#L941-L945

Added lines #L941 - L945 were not covered by tests
}

} // namespace autoware::motion::control::autonomous_emergency_braking

#include <rclcpp_components/register_node_macro.hpp>
Expand Down
Loading