diff --git a/.cppcheck_suppressions b/.cppcheck_suppressions
index f52eeb4e3ab2c..fc6685f2cafa3 100644
--- a/.cppcheck_suppressions
+++ b/.cppcheck_suppressions
@@ -1,17 +1,11 @@
*:*/test/*
checkersReport
-constParameterReference
-funcArgNamesDifferent
functionConst
functionStatic
missingInclude
missingIncludeSystem
noConstructor
-passedByValue
-redundantInitialization
-// cspell: ignore uninit
-uninitMemberVar
unknownMacro
unmatchedSuppression
unreadVariable
diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS
index 9f530e0dea9e3..e338a395482e9 100644
--- a/.github/CODEOWNERS
+++ b/.github/CODEOWNERS
@@ -5,6 +5,7 @@ common/autoware_grid_map_utils/** maxime.clement@tier4.jp
common/autoware_motion_utils/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/** ahmed.ebrahim@leodrive.ai
common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/** khalil@leodrive.ai
+common/autoware_path_distance_calculator/** isamu.takagi@tier4.jp
common/autoware_perception_rviz_plugin/** opensource@apex.ai shunsuke.miura@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp yoshi.ri@tier4.jp
common/autoware_point_types/** david.wong@tier4.jp max.schmeller@tier4.jp
common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp
@@ -24,7 +25,6 @@ common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp
common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp
common/object_recognition_utils/** shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yoshi.ri@tier4.jp
common/osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp
-common/path_distance_calculator/** isamu.takagi@tier4.jp
common/perception_utils/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp
common/polar_grid/** yukihiro.saito@tier4.jp
common/qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp
@@ -83,17 +83,17 @@ localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/*
localization/autoware_landmark_based_localizer/autoware_landmark_manager/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/autoware_pose_covariance_modifier/** melike@leodrive.ai
localization/autoware_stop_filter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
+localization/autoware_twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp
localization/geo_pose_projector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/gyro_odometer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/localization_error_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/localization_util/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/ndt_scan_matcher/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
-localization/pose2twist/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
+localization/autoware_pose2twist/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/pose_estimator_arbiter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/pose_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/pose_instability_detector/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
-localization/twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/yabloc/yabloc_common/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/yabloc/yabloc_image_processing/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/yabloc/yabloc_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
@@ -131,7 +131,7 @@ perception/autoware_radar_object_clustering/** satoshi.tanaka@tier4.jp shunsuke.
perception/autoware_radar_object_tracker/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp
perception/autoware_radar_tracks_msgs_converter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp
perception/autoware_raindrop_cluster_filter/** dai.nguyen@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp
-perception/autoware_shape_estimation/** yoshi.ri@tier4.jp yukihiro.saito@tier4.jp
+perception/autoware_shape_estimation/** kcolak@leodrive.ai yoshi.ri@tier4.jp yukihiro.saito@tier4.jp
perception/autoware_simple_object_merger/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp
perception/autoware_tensorrt_classifier/** kotaro.uetake@tier4.jp shunsuke.miura@tier4.jp
perception/autoware_tensorrt_yolox/** dan.umeda@tier4.jp manato.hirabayashi@tier4.jp
diff --git a/.github/workflows/build-and-test-daily.yaml b/.github/workflows/build-and-test-daily.yaml
index 0b21ba56640a7..66275444482b5 100644
--- a/.github/workflows/build-and-test-daily.yaml
+++ b/.github/workflows/build-and-test-daily.yaml
@@ -7,7 +7,7 @@ on:
jobs:
build-and-test-daily:
- runs-on: [self-hosted, linux, X64]
+ runs-on: [self-hosted, linux, X64, gpu]
container: ${{ matrix.container }}${{ matrix.container-suffix }}
strategy:
fail-fast: false
diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml
index 8d2158f3b911c..d41e6cf481b76 100644
--- a/.github/workflows/build-and-test-differential.yaml
+++ b/.github/workflows/build-and-test-differential.yaml
@@ -21,7 +21,7 @@ jobs:
build-and-test-differential:
needs: make-sure-label-is-present
if: ${{ needs.make-sure-label-is-present.outputs.result == 'true' }}
- runs-on: ubuntu-latest
+ runs-on: ${{ matrix.runner }}
container: ${{ matrix.container }}${{ matrix.container-suffix }}
strategy:
fail-fast: false
@@ -35,6 +35,10 @@ jobs:
- rosdistro: humble
container: ghcr.io/autowarefoundation/autoware:latest-autoware-universe
build-depends-repos: build_depends.repos
+ - container-suffix: -cuda
+ runner: [self-hosted, linux, X64, cpu]
+ - container-suffix: ""
+ runner: ubuntu-latest
steps:
- name: Set PR fetch depth
run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}"
diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml
index 85dc6c2fb89bf..716d6b8df5fbc 100644
--- a/.github/workflows/build-and-test.yaml
+++ b/.github/workflows/build-and-test.yaml
@@ -12,7 +12,7 @@ env:
jobs:
build-and-test:
- runs-on: [self-hosted, linux, X64]
+ runs-on: [self-hosted, linux, X64, gpu]
container: ${{ matrix.container }}${{ matrix.container-suffix }}
strategy:
fail-fast: false
diff --git a/README.md b/README.md
index 23d0b172554fd..35818990cee95 100644
--- a/README.md
+++ b/README.md
@@ -1,5 +1,7 @@
# Autoware Universe
+[![codecov](https://codecov.io/github/autowarefoundation/autoware.universe/graph/badge.svg?token=KQP68YQ65D)](https://codecov.io/github/autowarefoundation/autoware.universe)
+
## Welcome to Autoware Universe
Autoware Universe serves as a foundational pillar within the Autoware ecosystem, playing a critical role in enhancing the core functionalities of autonomous driving technologies.
diff --git a/codecov.yaml b/codecov.yaml
index ecc77815e97e6..255312a29ccf7 100644
--- a/codecov.yaml
+++ b/codecov.yaml
@@ -26,3 +26,7 @@ flag_management:
type: patch
target: 0% # Make CI always succeed
threshold: 100% # Make CI always succeed
+
+ignore:
+ - "**/test/*"
+ - "**/test/**/*"
diff --git a/common/.pages b/common/.pages
index 7a87ae2711e10..3b1326b5b6dd7 100644
--- a/common/.pages
+++ b/common/.pages
@@ -50,7 +50,7 @@ nav:
- 'traffic_light_recognition_marker_publisher': common/traffic_light_recognition_marker_publisher/Readme
- 'Node':
- 'Goal Distance Calculator': common/goal_distance_calculator/Readme
- - 'Path Distance Calculator': common/path_distance_calculator/Readme
+ - 'Path Distance Calculator': common/autoware_path_distance_calculator/Readme
- 'Others':
- 'autoware_ad_api_specs': common/autoware_ad_api_specs
- 'component_interface_specs': common/component_interface_specs
diff --git a/common/autoware_auto_common/test/test_template_utils.cpp b/common/autoware_auto_common/test/test_template_utils.cpp
index a670aaab83cfa..05e468dc4787e 100644
--- a/common/autoware_auto_common/test/test_template_utils.cpp
+++ b/common/autoware_auto_common/test/test_template_utils.cpp
@@ -27,7 +27,7 @@ struct FalseType
struct Foo
{
- CorrectType bar(CorrectType, const CorrectType &, CorrectType *) { return CorrectType{}; }
+ static CorrectType bar(CorrectType, const CorrectType &, CorrectType *) { return CorrectType{}; }
};
template class Expression, typename... Ts>
diff --git a/common/path_distance_calculator/CMakeLists.txt b/common/autoware_path_distance_calculator/CMakeLists.txt
similarity index 73%
rename from common/path_distance_calculator/CMakeLists.txt
rename to common/autoware_path_distance_calculator/CMakeLists.txt
index 0768371398def..6064164f2eff7 100644
--- a/common/path_distance_calculator/CMakeLists.txt
+++ b/common/autoware_path_distance_calculator/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
-project(path_distance_calculator)
+project(autoware_path_distance_calculator)
find_package(autoware_cmake REQUIRED)
autoware_package()
@@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
)
rclcpp_components_register_node(${PROJECT_NAME}
- PLUGIN "PathDistanceCalculator"
+ PLUGIN "autoware::path_distance_calculator::PathDistanceCalculator"
EXECUTABLE ${PROJECT_NAME}_node
)
diff --git a/common/path_distance_calculator/Readme.md b/common/autoware_path_distance_calculator/Readme.md
similarity index 97%
rename from common/path_distance_calculator/Readme.md
rename to common/autoware_path_distance_calculator/Readme.md
index fed0476047ba9..c6389c930f62a 100644
--- a/common/path_distance_calculator/Readme.md
+++ b/common/autoware_path_distance_calculator/Readme.md
@@ -1,4 +1,4 @@
-# path_distance_calculator
+# autoware_path_distance_calculator
## Purpose
diff --git a/common/path_distance_calculator/launch/path_distance_calculator.launch.xml b/common/autoware_path_distance_calculator/launch/path_distance_calculator.launch.xml
similarity index 68%
rename from common/path_distance_calculator/launch/path_distance_calculator.launch.xml
rename to common/autoware_path_distance_calculator/launch/path_distance_calculator.launch.xml
index 92805fb10c49a..15ab838c7da7a 100644
--- a/common/path_distance_calculator/launch/path_distance_calculator.launch.xml
+++ b/common/autoware_path_distance_calculator/launch/path_distance_calculator.launch.xml
@@ -1,7 +1,7 @@
-
+
diff --git a/common/path_distance_calculator/package.xml b/common/autoware_path_distance_calculator/package.xml
similarity index 86%
rename from common/path_distance_calculator/package.xml
rename to common/autoware_path_distance_calculator/package.xml
index 1921cbb1c4a20..f6410ffb24dc5 100644
--- a/common/path_distance_calculator/package.xml
+++ b/common/autoware_path_distance_calculator/package.xml
@@ -1,9 +1,9 @@
- path_distance_calculator
+ autoware_path_distance_calculator
0.0.0
- The path_distance_calculator package
+ The autoware_path_distance_calculator package
Takagi, Isamu
Apache License 2.0
diff --git a/common/path_distance_calculator/src/path_distance_calculator.cpp b/common/autoware_path_distance_calculator/src/path_distance_calculator.cpp
similarity index 91%
rename from common/path_distance_calculator/src/path_distance_calculator.cpp
rename to common/autoware_path_distance_calculator/src/path_distance_calculator.cpp
index 833c806cdd6db..b91752e547196 100644
--- a/common/path_distance_calculator/src/path_distance_calculator.cpp
+++ b/common/autoware_path_distance_calculator/src/path_distance_calculator.cpp
@@ -22,6 +22,8 @@
#include
#include
+namespace autoware::path_distance_calculator
+{
PathDistanceCalculator::PathDistanceCalculator(const rclcpp::NodeOptions & options)
: Node("path_distance_calculator", options), self_pose_listener_(this)
{
@@ -54,6 +56,6 @@ PathDistanceCalculator::PathDistanceCalculator(const rclcpp::NodeOptions & optio
pub_dist_->publish(msg);
});
}
-
+} // namespace autoware::path_distance_calculator
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(PathDistanceCalculator)
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::path_distance_calculator::PathDistanceCalculator)
diff --git a/common/path_distance_calculator/src/path_distance_calculator.hpp b/common/autoware_path_distance_calculator/src/path_distance_calculator.hpp
similarity index 93%
rename from common/path_distance_calculator/src/path_distance_calculator.hpp
rename to common/autoware_path_distance_calculator/src/path_distance_calculator.hpp
index 6624f316401df..ff83483676467 100644
--- a/common/path_distance_calculator/src/path_distance_calculator.hpp
+++ b/common/autoware_path_distance_calculator/src/path_distance_calculator.hpp
@@ -22,6 +22,9 @@
#include
#include
+namespace autoware::path_distance_calculator
+{
+
class PathDistanceCalculator : public rclcpp::Node
{
public:
@@ -35,4 +38,6 @@ class PathDistanceCalculator : public rclcpp::Node
autoware::universe_utils::SelfPoseListener self_pose_listener_;
};
+} // namespace autoware::path_distance_calculator
+
#endif // PATH_DISTANCE_CALCULATOR_HPP_
diff --git a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp b/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp
index 8d29900e1da26..fed20e24f9787 100644
--- a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp
+++ b/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp
@@ -104,7 +104,7 @@ get_2d_shape_marker_ptr(
AUTOWARE_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr
get_label_marker_ptr(
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
- const std::string label, const std_msgs::msg::ColorRGBA & color_rgba);
+ const std::string & label, const std_msgs::msg::ColorRGBA & color_rgba);
AUTOWARE_PERCEPTION_RVIZ_PLUGIN_PUBLIC visualization_msgs::msg::Marker::SharedPtr
get_existence_probability_marker_ptr(
diff --git a/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp
index 910bd6ed815e6..9c25c2dc3781e 100644
--- a/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp
+++ b/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp
@@ -459,7 +459,7 @@ visualization_msgs::msg::Marker::SharedPtr get_uuid_marker_ptr(
visualization_msgs::msg::Marker::SharedPtr get_label_marker_ptr(
const geometry_msgs::msg::Point & centroid, const geometry_msgs::msg::Quaternion & orientation,
- const std::string label, const std_msgs::msg::ColorRGBA & color_rgba)
+ const std::string & label, const std_msgs::msg::ColorRGBA & color_rgba)
{
auto marker_ptr = std::make_shared();
marker_ptr->type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING;
diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp
new file mode 100644
index 0000000000000..175d1934e973d
--- /dev/null
+++ b/common/autoware_universe_utils/include/autoware/universe_utils/ros/static_transform_buffer.hpp
@@ -0,0 +1,165 @@
+// Copyright 2024 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_
+#define AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_
+
+#include "autoware/universe_utils/ros/transform_listener.hpp"
+
+#include
+#include
+#include
+
+#include
+
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+namespace std
+{
+template <>
+struct hash>
+{
+ size_t operator()(const std::pair & p) const
+ {
+ size_t h1 = std::hash{}(p.first);
+ size_t h2 = std::hash{}(p.second);
+ return h1 ^ (h2 << 1u);
+ }
+};
+} // namespace std
+
+namespace autoware::universe_utils
+{
+using std::chrono_literals::operator""ms;
+using Key = std::pair;
+struct PairEqual
+{
+ bool operator()(const Key & p1, const Key & p2) const
+ {
+ return p1.first == p2.first && p1.second == p2.second;
+ }
+};
+using TFMap = std::unordered_map, PairEqual>;
+
+class StaticTransformBuffer
+{
+public:
+ StaticTransformBuffer() = default;
+
+ /**
+ * @brief Retrieves a transform between two static frames.
+ *
+ * This function attempts to retrieve a transform between the target frame and the source frame.
+ * If success, the transform matrix is set to the output parameter and the function returns true.
+ * Otherwise, transform matrix is set to identity and the function returns false. Transform
+ * Listener is destroyed after function call.
+ *
+ * @param node A pointer to the ROS node.
+ * @param target_frame The target frame.
+ * @param source_frame The source frame.
+ * @param eigen_transform The output Eigen transform matrix. Is set to identity if the transform
+ * is not found.
+ * @return True if the transform was successfully retrieved, false otherwise.
+ */
+ bool getTransform(
+ rclcpp::Node * node, const std::string & target_frame, const std::string & source_frame,
+ Eigen::Matrix4f & eigen_transform)
+ {
+ auto key = std::make_pair(target_frame, source_frame);
+ auto key_inv = std::make_pair(source_frame, target_frame);
+
+ // Check if the transform is already in the buffer
+ auto it = buffer_.find(key);
+ if (it != buffer_.end()) {
+ eigen_transform = it->second;
+ return true;
+ }
+
+ // Check if the inverse transform is already in the buffer
+ auto it_inv = buffer_.find(key_inv);
+ if (it_inv != buffer_.end()) {
+ eigen_transform = it_inv->second.inverse();
+ buffer_[key] = eigen_transform;
+ return true;
+ }
+
+ // Check if transform is needed
+ if (target_frame == source_frame) {
+ eigen_transform = Eigen::Matrix4f::Identity();
+ buffer_[key] = eigen_transform;
+ return true;
+ }
+
+ // Get the transform from the TF tree
+ auto tf_listener = std::make_unique(node);
+ auto tf = tf_listener->getTransform(
+ target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms));
+ RCLCPP_DEBUG(
+ node->get_logger(), "Trying to enqueue %s -> %s transform to static TFs buffer...",
+ target_frame.c_str(), source_frame.c_str());
+ if (tf == nullptr) {
+ eigen_transform = Eigen::Matrix4f::Identity();
+ return false;
+ }
+ pcl_ros::transformAsMatrix(*tf, eigen_transform);
+ buffer_[key] = eigen_transform;
+ return true;
+ }
+
+ /**
+ * Transforms a point cloud from one frame to another.
+ *
+ * @param node A pointer to the ROS node.
+ * @param target_frame The target frame to transform the point cloud to.
+ * @param cloud_in The input point cloud to be transformed.
+ * @param cloud_out The transformed point cloud.
+ * @return True if the transformation is successful, false otherwise.
+ */
+ bool transformPointcloud(
+ rclcpp::Node * node, const std::string & target_frame,
+ const sensor_msgs::msg::PointCloud2 & cloud_in, sensor_msgs::msg::PointCloud2 & cloud_out)
+ {
+ if (
+ pcl::getFieldIndex(cloud_in, "x") == -1 || pcl::getFieldIndex(cloud_in, "y") == -1 ||
+ pcl::getFieldIndex(cloud_in, "z") == -1) {
+ RCLCPP_ERROR(node->get_logger(), "Input pointcloud does not have xyz fields");
+ return false;
+ }
+ if (target_frame == cloud_in.header.frame_id) {
+ cloud_out = cloud_in;
+ return true;
+ }
+ Eigen::Matrix4f eigen_transform;
+ if (!getTransform(node, target_frame, cloud_in.header.frame_id, eigen_transform)) {
+ return false;
+ }
+ pcl_ros::transformPointCloud(eigen_transform, cloud_in, cloud_out);
+ cloud_out.header.frame_id = target_frame;
+ return true;
+ }
+
+private:
+ TFMap buffer_;
+};
+
+} // namespace autoware::universe_utils
+
+#endif // AUTOWARE__UNIVERSE_UTILS__ROS__STATIC_TRANSFORM_BUFFER_HPP_
diff --git a/common/autoware_universe_utils/package.xml b/common/autoware_universe_utils/package.xml
index de0461b5a841d..b4809e720b8d4 100644
--- a/common/autoware_universe_utils/package.xml
+++ b/common/autoware_universe_utils/package.xml
@@ -24,6 +24,7 @@
pcl_ros
rclcpp
tf2
+ tf2_eigen
tf2_geometry_msgs
tier4_debug_msgs
tier4_planning_msgs
diff --git a/common/autoware_universe_utils/src/geometry/random_convex_polygon.cpp b/common/autoware_universe_utils/src/geometry/random_convex_polygon.cpp
index d857956806554..3096964c6fd01 100644
--- a/common/autoware_universe_utils/src/geometry/random_convex_polygon.cpp
+++ b/common/autoware_universe_utils/src/geometry/random_convex_polygon.cpp
@@ -31,8 +31,11 @@ struct VectorsWithMin
};
VectorsWithMin prepare_coordinate_vectors(
- const size_t nb_vertices, std::uniform_real_distribution & random_double,
- std::uniform_int_distribution & random_bool, std::default_random_engine & random_engine)
+ const size_t nb_vertices,
+ std::uniform_real_distribution &
+ random_double, // cppcheck-suppress constParameterReference
+ std::uniform_int_distribution & random_bool, // cppcheck-suppress constParameterReference
+ std::default_random_engine & random_engine)
{
std::vector v;
for (auto i = 0UL; i < nb_vertices; ++i) {
diff --git a/common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp b/common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp
new file mode 100644
index 0000000000000..5200378e3bf52
--- /dev/null
+++ b/common/autoware_universe_utils/test/src/ros/test_static_transform_buffer.cpp
@@ -0,0 +1,210 @@
+// Copyright 2024 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "autoware/universe_utils/ros/static_transform_buffer.hpp"
+
+#include
+#include
+
+#include
+#include
+
+#include
+
+class TestStaticTransformBuffer : public ::testing::Test
+{
+protected:
+ std::shared_ptr node_{nullptr};
+ std::shared_ptr static_tf_buffer_{nullptr};
+ std::shared_ptr tf_broadcaster_;
+ geometry_msgs::msg::TransformStamped tf_base_to_lidar_;
+ Eigen::Matrix4f eigen_base_to_lidar_;
+ std::unique_ptr cloud_in_;
+
+ geometry_msgs::msg::TransformStamped generateTransformMsg(
+ const int32_t seconds, const uint32_t nanoseconds, const std::string & parent_frame,
+ const std::string & child_frame, double x, double y, double z, double qx, double qy, double qz,
+ double qw)
+ {
+ rclcpp::Time timestamp(seconds, nanoseconds, RCL_ROS_TIME);
+ geometry_msgs::msg::TransformStamped tf_msg;
+ tf_msg.header.stamp = timestamp;
+ tf_msg.header.frame_id = parent_frame;
+ tf_msg.child_frame_id = child_frame;
+ tf_msg.transform.translation.x = x;
+ tf_msg.transform.translation.y = y;
+ tf_msg.transform.translation.z = z;
+ tf_msg.transform.rotation.x = qx;
+ tf_msg.transform.rotation.y = qy;
+ tf_msg.transform.rotation.z = qz;
+ tf_msg.transform.rotation.w = qw;
+ return tf_msg;
+ }
+
+ void SetUp() override
+ {
+ node_ = std::make_shared("test_static_transform_buffer");
+ static_tf_buffer_ = std::make_shared();
+ tf_broadcaster_ = std::make_shared(node_);
+
+ tf_base_to_lidar_ = generateTransformMsg(
+ 10, 100'000'000, "base_link", "lidar_top", 0.690, 0.000, 2.100, -0.007, -0.007, 0.692, 0.722);
+ eigen_base_to_lidar_ = tf2::transformToEigen(tf_base_to_lidar_).matrix().cast();
+ tf_broadcaster_->sendTransform(tf_base_to_lidar_);
+ cloud_in_ = std::make_unique();
+
+ // Set up the fields for x, y, and z coordinates
+ cloud_in_->fields.resize(3);
+ sensor_msgs::PointCloud2Modifier modifier(*cloud_in_);
+ modifier.setPointCloud2FieldsByString(1, "xyz");
+
+ // Resize the cloud to hold points_per_pointcloud_ points
+ modifier.resize(10);
+
+ // Create an iterator for the x, y, z fields
+ sensor_msgs::PointCloud2Iterator iter_x(*cloud_in_, "x");
+ sensor_msgs::PointCloud2Iterator iter_y(*cloud_in_, "y");
+ sensor_msgs::PointCloud2Iterator iter_z(*cloud_in_, "z");
+
+ // Populate the point cloud
+ for (size_t i = 0; i < modifier.size(); ++i, ++iter_x, ++iter_y, ++iter_z) {
+ *iter_x = static_cast(i);
+ *iter_y = static_cast(i);
+ *iter_z = static_cast(i);
+ }
+
+ // Set up cloud header
+ cloud_in_->header.frame_id = "lidar_top";
+ cloud_in_->header.stamp = rclcpp::Time(10, 100'000'000);
+
+ ASSERT_TRUE(rclcpp::ok());
+ }
+
+ void TearDown() override { static_tf_buffer_.reset(); }
+};
+
+TEST_F(TestStaticTransformBuffer, TestTransformNoExist)
+{
+ Eigen::Matrix4f transform;
+ auto success = static_tf_buffer_->getTransform(node_.get(), "base_link", "fake_link", transform);
+ EXPECT_TRUE(transform.isIdentity());
+ EXPECT_FALSE(success);
+}
+
+TEST_F(TestStaticTransformBuffer, TestTransformBase)
+{
+ Eigen::Matrix4f eigen_base_to_lidar;
+ auto success =
+ static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_base_to_lidar);
+ EXPECT_TRUE(eigen_base_to_lidar.isApprox(eigen_base_to_lidar_, 0.001));
+ EXPECT_TRUE(success);
+}
+
+TEST_F(TestStaticTransformBuffer, TestTransformSameFrame)
+{
+ Eigen::Matrix4f eigen_base_to_base;
+ auto success =
+ static_tf_buffer_->getTransform(node_.get(), "base_link", "base_link", eigen_base_to_base);
+ EXPECT_TRUE(eigen_base_to_base.isApprox(Eigen::Matrix4f::Identity(), 0.001));
+ EXPECT_TRUE(success);
+}
+
+TEST_F(TestStaticTransformBuffer, TestTransformInverse)
+{
+ Eigen::Matrix4f eigen_lidar_to_base;
+ auto success =
+ static_tf_buffer_->getTransform(node_.get(), "lidar_top", "base_link", eigen_lidar_to_base);
+ EXPECT_TRUE(eigen_lidar_to_base.isApprox(eigen_base_to_lidar_.inverse(), 0.001));
+ EXPECT_TRUE(success);
+}
+
+TEST_F(TestStaticTransformBuffer, TestTransformMultipleCall)
+{
+ Eigen::Matrix4f eigen_transform;
+ EXPECT_FALSE(
+ static_tf_buffer_->getTransform(node_.get(), "base_link", "fake_link", eigen_transform));
+ EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001));
+ EXPECT_TRUE(
+ static_tf_buffer_->getTransform(node_.get(), "lidar_top", "base_link", eigen_transform));
+ EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_.inverse(), 0.001));
+ EXPECT_TRUE(
+ static_tf_buffer_->getTransform(node_.get(), "fake_link", "fake_link", eigen_transform));
+ EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001));
+ EXPECT_TRUE(
+ static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_transform));
+ EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_, 0.001));
+ EXPECT_FALSE(
+ static_tf_buffer_->getTransform(node_.get(), "fake_link", "lidar_top", eigen_transform));
+ EXPECT_TRUE(eigen_transform.isApprox(Eigen::Matrix4f::Identity(), 0.001));
+ EXPECT_TRUE(
+ static_tf_buffer_->getTransform(node_.get(), "base_link", "lidar_top", eigen_transform));
+ EXPECT_TRUE(eigen_transform.isApprox(eigen_base_to_lidar_, 0.001));
+}
+
+TEST_F(TestStaticTransformBuffer, TestTransformEmptyPointCloud)
+{
+ auto cloud_in = std::make_unique();
+ cloud_in->header.frame_id = "lidar_top";
+ cloud_in->header.stamp = rclcpp::Time(10, 100'000'000);
+ auto cloud_out = std::make_unique();
+
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out));
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out));
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out));
+}
+
+TEST_F(TestStaticTransformBuffer, TestTransformEmptyPointCloudNoHeader)
+{
+ auto cloud_in = std::make_unique();
+ auto cloud_out = std::make_unique();
+
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out));
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out));
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out));
+}
+
+TEST_F(TestStaticTransformBuffer, TestTransformPointCloud)
+{
+ auto cloud_out = std::make_unique();
+
+ // Transform cloud with header
+ EXPECT_TRUE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in_, *cloud_out));
+ EXPECT_TRUE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in_, *cloud_out));
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in_, *cloud_out));
+}
+
+TEST_F(TestStaticTransformBuffer, TestTransformPointCloudNoHeader)
+{
+ auto cloud_out = std::make_unique();
+
+ // Transform cloud without header
+ auto cloud_in = std::make_unique(*cloud_in_);
+ cloud_in->header.frame_id = "";
+ cloud_in->header.stamp = rclcpp::Time(0, 0);
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "lidar_top", *cloud_in, *cloud_out));
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "base_link", *cloud_in, *cloud_out));
+ EXPECT_FALSE(
+ static_tf_buffer_->transformPointcloud(node_.get(), "fake_link", *cloud_in, *cloud_out));
+}
diff --git a/common/tensorrt_common/src/tensorrt_common.cpp b/common/tensorrt_common/src/tensorrt_common.cpp
index 87e8f422dd3f8..74fd331b40ae7 100644
--- a/common/tensorrt_common/src/tensorrt_common.cpp
+++ b/common/tensorrt_common/src/tensorrt_common.cpp
@@ -137,6 +137,7 @@ void TrtCommon::setup()
is_initialized_ = false;
return;
}
+ // cppcheck-suppress unreadVariable
std::string engine_path = model_file_path_;
if (model_file_path_.extension() == ".engine") {
std::cout << "Load ... " << model_file_path_ << std::endl;
@@ -193,6 +194,7 @@ void TrtCommon::setup()
logger_.stop_throttle(log_thread);
logger_.log(nvinfer1::ILogger::Severity::kINFO, "End build engine");
}
+ // cppcheck-suppress unreadVariable
engine_path = cache_engine_path;
} else {
is_initialized_ = false;
diff --git a/control/autoware_autonomous_emergency_braking/CMakeLists.txt b/control/autoware_autonomous_emergency_braking/CMakeLists.txt
index 85290c6c66730..9f7a64c18da9a 100644
--- a/control/autoware_autonomous_emergency_braking/CMakeLists.txt
+++ b/control/autoware_autonomous_emergency_braking/CMakeLists.txt
@@ -30,8 +30,11 @@ rclcpp_components_register_node(${AEB_NODE}
)
if(BUILD_TESTING)
- find_package(ament_lint_auto REQUIRED)
- ament_lint_auto_find_test_dependencies()
+ ament_add_ros_isolated_gtest(test_aeb
+ test/test.cpp)
+
+target_link_libraries(test_aeb ${AEB_NODE})
+
endif()
ament_auto_package(
diff --git a/control/autoware_autonomous_emergency_braking/README.md b/control/autoware_autonomous_emergency_braking/README.md
index db27ca1b4f699..1382a24d98b0a 100644
--- a/control/autoware_autonomous_emergency_braking/README.md
+++ b/control/autoware_autonomous_emergency_braking/README.md
@@ -197,6 +197,7 @@ When vehicle odometry information is faulty, it is possible that the MPC fails t
| use_predicted_trajectory | [-] | bool | flag to use the predicted path from the control module | true |
| use_imu_path | [-] | bool | flag to use the predicted path generated by sensor data | true |
| use_object_velocity_calculation | [-] | bool | flag to use the object velocity calculation. If set to false, object velocity is set to 0 [m/s] | true |
+| check_autoware_state | [-] | bool | flag to enable or disable autoware state check. If set to false, the AEB module will run even when the ego vehicle is not in AUTONOMOUS state. | true |
| detection_range_min_height | [m] | double | minimum hight of detection range used for avoiding the ghost brake by false positive point clouds | 0.0 |
| detection_range_max_height_margin | [m] | double | margin for maximum hight of detection range used for avoiding the ghost brake by false positive point clouds. `detection_range_max_height = vehicle_height + detection_range_max_height_margin` | 0.0 |
| voxel_grid_x | [m] | double | down sampling parameters of x-axis for voxel grid filter | 0.05 |
diff --git a/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml
index 25db9448f758b..f13e95c6db8e5 100644
--- a/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml
+++ b/control/autoware_autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml
@@ -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
diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp
index 9fd6d0192439c..24eaa8516a732 100644
--- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp
+++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp
@@ -71,6 +71,9 @@ using Vector3 = geometry_msgs::msg::Vector3;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
+/**
+ * @brief Struct to store object data
+ */
struct ObjectData
{
rclcpp::Time stamp;
@@ -80,22 +83,44 @@ struct ObjectData
double distance_to_object{0.0};
};
+/**
+ * @brief Class to manage collision data
+ */
class CollisionDataKeeper
{
public:
+ /**
+ * @brief Constructor for CollisionDataKeeper
+ * @param clock Shared pointer to the clock
+ */
explicit CollisionDataKeeper(rclcpp::Clock::SharedPtr clock) { clock_ = clock; }
+ /**
+ * @brief Set timeout values for collision and obstacle data
+ * @param collision_keep_time Time to keep collision data
+ * @param previous_obstacle_keep_time Time to keep previous obstacle data
+ */
void setTimeout(const double collision_keep_time, const double previous_obstacle_keep_time)
{
collision_keep_time_ = collision_keep_time;
previous_obstacle_keep_time_ = previous_obstacle_keep_time;
}
+ /**
+ * @brief Get timeout values for collision and obstacle data
+ * @return Pair of collision and obstacle data timeout values
+ */
std::pair getTimeout()
{
return {collision_keep_time_, previous_obstacle_keep_time_};
}
+ /**
+ * @brief Check if object data has expired
+ * @param data Optional reference to the object data
+ * @param timeout Timeout value to check against
+ * @return True if object data has expired, false otherwise
+ */
bool checkObjectDataExpired(std::optional & data, const double timeout)
{
if (!data.has_value()) return true;
@@ -109,38 +134,70 @@ class CollisionDataKeeper
return false;
}
+ /**
+ * @brief Check if collision data has expired
+ * @return True if collision data has expired, false otherwise
+ */
bool checkCollisionExpired()
{
return this->checkObjectDataExpired(closest_object_, collision_keep_time_);
}
+ /**
+ * @brief Check if previous object data has expired
+ * @return True if previous object data has expired, false otherwise
+ */
bool checkPreviousObjectDataExpired()
{
return this->checkObjectDataExpired(prev_closest_object_, previous_obstacle_keep_time_);
}
+ /**
+ * @brief Get the closest object data
+ * @return Object data of the closest object
+ */
[[nodiscard]] ObjectData get() const
{
return (closest_object_.has_value()) ? closest_object_.value() : ObjectData();
}
+ /**
+ * @brief Get the previous closest object data
+ * @return Object data of the previous closest object
+ */
[[nodiscard]] ObjectData getPreviousObjectData() const
{
return (prev_closest_object_.has_value()) ? prev_closest_object_.value() : ObjectData();
}
+ /**
+ * @brief Set collision data
+ * @param data Object data to set
+ */
void setCollisionData(const ObjectData & data)
{
closest_object_ = std::make_optional(data);
}
+ /**
+ * @brief Set previous object data
+ * @param data Object data to set
+ */
void setPreviousObjectData(const ObjectData & data)
{
prev_closest_object_ = std::make_optional(data);
}
+ /**
+ * @brief Reset the obstacle velocity history
+ */
void resetVelocityHistory() { obstacle_velocity_history_.clear(); }
+ /**
+ * @brief Update the velocity history with current object velocity
+ * @param current_object_velocity Current object velocity
+ * @param current_object_velocity_time_stamp Timestamp of the current object velocity
+ */
void updateVelocityHistory(
const double current_object_velocity, const rclcpp::Time & current_object_velocity_time_stamp)
{
@@ -158,6 +215,10 @@ class CollisionDataKeeper
current_object_velocity, current_object_velocity_time_stamp);
}
+ /**
+ * @brief Get the median obstacle velocity from history
+ * @return Optional median obstacle velocity
+ */
[[nodiscard]] std::optional getMedianObstacleVelocity() const
{
if (obstacle_velocity_history_.empty()) return std::nullopt;
@@ -177,6 +238,13 @@ class CollisionDataKeeper
return (vel1 + vel2) / 2.0;
}
+ /**
+ * @brief Calculate object speed from velocity history
+ * @param closest_object Closest object data
+ * @param path Ego vehicle path
+ * @param current_ego_speed Current ego vehicle speed
+ * @return Optional calculated object speed
+ */
std::optional calcObjectSpeedFromHistory(
const ObjectData & closest_object, const Path & path, const double current_ego_speed)
{
@@ -241,9 +309,16 @@ class CollisionDataKeeper
rclcpp::Clock::SharedPtr clock_;
};
+/**
+ * @brief Autonomous Emergency Braking (AEB) node
+ */
class AEB : public rclcpp::Node
{
public:
+ /**
+ * @brief Constructor for AEB
+ * @param node_options Options for the node
+ */
explicit AEB(const rclcpp::NodeOptions & node_options);
// subscriber
@@ -260,57 +335,163 @@ class AEB : public rclcpp::Node
this, "/autoware/state"};
// publisher
rclcpp::Publisher::SharedPtr pub_obstacle_pointcloud_;
- rclcpp::Publisher::SharedPtr debug_ego_path_publisher_; // debug
+ rclcpp::Publisher::SharedPtr debug_marker_publisher_;
+ rclcpp::Publisher::SharedPtr info_marker_publisher_;
// timer
rclcpp::TimerBase::SharedPtr timer_;
// callback
+ /**
+ * @brief Callback for point cloud messages
+ * @param input_msg Shared pointer to the point cloud message
+ */
void onPointCloud(const PointCloud2::ConstSharedPtr input_msg);
+
+ /**
+ * @brief Callback for IMU messages
+ * @param input_msg Shared pointer to the IMU message
+ */
void onImu(const Imu::ConstSharedPtr input_msg);
+
+ /**
+ * @brief Timer callback function
+ */
void onTimer();
+
+ /**
+ * @brief Callback for parameter updates
+ * @param parameters Vector of updated parameters
+ * @return Set parameters result
+ */
rcl_interfaces::msg::SetParametersResult onParameter(
const std::vector & parameters);
+ /**
+ * @brief Fetch the latest data from subscribers
+ * @return True if data fetch was successful, false otherwise
+ */
bool fetchLatestData();
- // main function
+ /**
+ * @brief Diagnostic check for collisions
+ * @param stat Diagnostic status wrapper
+ */
void onCheckCollision(DiagnosticStatusWrapper & stat);
+
+ /**
+ * @brief Check for collisions
+ * @param debug_markers Marker array for debugging
+ * @return True if a collision is detected, false otherwise
+ */
bool checkCollision(MarkerArray & debug_markers);
+
+ /**
+ * @brief Check if there is a collision with the closest object
+ * @param current_v Current velocity of the ego vehicle
+ * @param closest_object Data of the closest object
+ * @return True if a collision is detected, false otherwise
+ */
bool hasCollision(const double current_v, const ObjectData & closest_object);
+ /**
+ * @brief Generate the ego vehicle path
+ * @param curr_v Current velocity of the ego vehicle
+ * @param curr_w Current angular velocity of the ego vehicle
+ * @return Generated ego path
+ */
Path generateEgoPath(const double curr_v, const double curr_w);
+
+ /**
+ * @brief Generate the ego vehicle path from the predicted trajectory
+ * @param predicted_traj Predicted trajectory of the ego vehicle
+ * @return Optional generated ego path
+ */
std::optional generateEgoPath(const Trajectory & predicted_traj);
+
+ /**
+ * @brief Generate the footprint of the path with extra width margin
+ * @param path Ego vehicle path
+ * @param extra_width_margin Extra width margin for the footprint
+ * @return Vector of polygons representing the path footprint
+ */
std::vector generatePathFootprint(const Path & path, const double extra_width_margin);
+ /**
+ * @brief Create object data using point cloud clusters
+ * @param ego_path Ego vehicle path
+ * @param ego_polys Polygons representing the ego vehicle footprint
+ * @param stamp Timestamp of the data
+ * @param objects Vector to store the created object data
+ * @param obstacle_points_ptr Pointer to the point cloud of obstacles
+ */
void createObjectDataUsingPointCloudClusters(
const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp,
std::vector & objects,
const pcl::PointCloud::Ptr obstacle_points_ptr);
+ /**
+ * @brief Create object data using predicted objects
+ * @param ego_path Ego vehicle path
+ * @param ego_polys Polygons representing the ego vehicle footprint
+ * @param objects Vector to store the created object data
+ */
void createObjectDataUsingPredictedObjects(
const Path & ego_path, const std::vector & ego_polys,
std::vector & objects);
+ /**
+ * @brief Crop the point cloud with the ego vehicle footprint path
+ * @param ego_polys Polygons representing the ego vehicle footprint
+ * @param filtered_objects Pointer to the filtered point cloud of obstacles
+ */
void cropPointCloudWithEgoFootprintPath(
const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects);
- void createObjectDataUsingPointCloudClusters(
- const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp,
- std::vector & objects);
- void cropPointCloudWithEgoFootprintPath(const std::vector & ego_polys);
-
+ /**
+ * @brief Add a marker for debugging
+ * @param current_time Current time
+ * @param path Ego vehicle path
+ * @param polygons Polygons representing the ego vehicle footprint
+ * @param objects Vector of object data
+ * @param closest_object Optional data of the closest object
+ * @param color_r Red color component
+ * @param color_g Green color component
+ * @param color_b Blue color component
+ * @param color_a Alpha (transparency) component
+ * @param ns Namespace for the marker
+ * @param debug_markers Marker array for debugging
+ */
void addMarker(
const rclcpp::Time & current_time, const Path & path, const std::vector & polygons,
const std::vector & objects, const std::optional & closest_object,
const double color_r, const double color_g, const double color_b, const double color_a,
const std::string & ns, MarkerArray & debug_markers);
+ /**
+ * @brief Add a collision marker for debugging
+ * @param data Data of the collision object
+ * @param debug_markers Marker array for debugging
+ */
void addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers);
+ /**
+ * @brief Add an info marker stop wall in front of the ego vehicle
+ * @param markers Data of the closest object
+ */
+ void addVirtualStopWallMarker(MarkerArray & markers);
+
+ /**
+ * @brief Calculate object speed from history
+ * @param closest_object Data of the closest object
+ * @param path Ego vehicle path
+ * @param current_ego_speed Current speed of the ego vehicle
+ * @return Optional calculated object speed
+ */
std::optional calcObjectSpeedFromHistory(
const ObjectData & closest_object, const Path & path, const double current_ego_speed);
+ // Member variables
PointCloud2::SharedPtr obstacle_ros_pointcloud_ptr_{nullptr};
VelocityReport::ConstSharedPtr current_velocity_ptr_{nullptr};
Vector3::SharedPtr angular_velocity_ptr_{nullptr};
@@ -327,7 +508,7 @@ class AEB : public rclcpp::Node
// diag
Updater updater_{this};
- // member variables
+ // Member variables
bool publish_debug_pointcloud_;
bool publish_debug_markers_;
bool use_predicted_trajectory_;
@@ -335,6 +516,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_;
diff --git a/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml b/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml
index fe0df41ca89c7..34d0492799577 100644
--- a/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml
+++ b/control/autoware_autonomous_emergency_braking/launch/autoware_autonomous_emergency_braking.launch.xml
@@ -3,7 +3,6 @@
-
diff --git a/control/autoware_autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml
index d0c75f893cd2d..173d419bf6d9a 100644
--- a/control/autoware_autonomous_emergency_braking/package.xml
+++ b/control/autoware_autonomous_emergency_braking/package.xml
@@ -14,12 +14,17 @@
ament_cmake
autoware_cmake
+ ament_cmake_ros
+ ament_lint_auto
+ autoware_lint_common
+ autoware_test_utils
autoware_control_msgs
autoware_motion_utils
autoware_planning_msgs
autoware_pointcloud_preprocessor
autoware_system_msgs
+ autoware_test_utils
autoware_universe_utils
autoware_vehicle_info_utils
autoware_vehicle_msgs
@@ -38,9 +43,6 @@
tf2_ros
visualization_msgs
- ament_lint_auto
- autoware_lint_common
-
ament_cmake
diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp
index 69bedd02d201b..cd97a8301ad9d 100644
--- a/control/autoware_autonomous_emergency_braking/src/node.cpp
+++ b/control/autoware_autonomous_emergency_braking/src/node.cpp
@@ -125,7 +125,8 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
{
pub_obstacle_pointcloud_ =
this->create_publisher("~/debug/obstacle_pointcloud", 1);
- debug_ego_path_publisher_ = this->create_publisher("~/debug/markers", 1);
+ debug_marker_publisher_ = this->create_publisher("~/debug/markers", 1);
+ info_marker_publisher_ = this->create_publisher("~/info/markers", 1);
}
// Diagnostics
{
@@ -140,6 +141,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options)
use_pointcloud_data_ = declare_parameter("use_pointcloud_data");
use_predicted_object_data_ = declare_parameter("use_predicted_object_data");
use_object_velocity_calculation_ = declare_parameter("use_object_velocity_calculation");
+ check_autoware_state_ = declare_parameter("check_autoware_state");
path_footprint_extra_margin_ = declare_parameter("path_footprint_extra_margin");
detection_range_min_height_ = declare_parameter("detection_range_min_height");
detection_range_max_height_margin_ =
@@ -193,6 +195,7 @@ rcl_interfaces::msg::SetParametersResult AEB::onParameter(
updateParam(parameters, "use_predicted_object_data", use_predicted_object_data_);
updateParam(
parameters, "use_object_velocity_calculation", use_object_velocity_calculation_);
+ updateParam(parameters, "check_autoware_state", check_autoware_state_);
updateParam(parameters, "path_footprint_extra_margin", path_footprint_extra_margin_);
updateParam(parameters, "detection_range_min_height", detection_range_min_height_);
updateParam(
@@ -363,7 +366,7 @@ bool AEB::fetchLatestData()
}
autoware_state_ = sub_autoware_state_.takeData();
- if (!autoware_state_) {
+ if (check_autoware_state_ && !autoware_state_) {
return missing("autoware_state");
}
@@ -373,6 +376,7 @@ bool AEB::fetchLatestData()
void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
{
MarkerArray debug_markers;
+ MarkerArray info_markers;
checkCollision(debug_markers);
if (!collision_data_keeper_.checkCollisionExpired()) {
@@ -386,6 +390,7 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
if (publish_debug_markers_) {
addCollisionMarker(data, debug_markers);
}
+ addVirtualStopWallMarker(info_markers);
} else {
const std::string error_msg = "[AEB]: No Collision";
const auto diag_level = DiagnosticStatus::OK;
@@ -393,7 +398,8 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat)
}
// publish debug markers
- debug_ego_path_publisher_->publish(debug_markers);
+ debug_marker_publisher_->publish(debug_markers);
+ info_marker_publisher_->publish(info_markers);
}
bool AEB::checkCollision(MarkerArray & debug_markers)
@@ -406,7 +412,7 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
}
// if not driving, disable aeb
- if (autoware_state_->state != AutowareState::DRIVING) {
+ if (check_autoware_state_ && autoware_state_->state != AutowareState::DRIVING) {
return false;
}
@@ -501,7 +507,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
};
// Data of filtered point cloud
- pcl::PointCloud::Ptr filtered_objects(new PointCloud);
+ pcl::PointCloud::Ptr filtered_objects =
+ pcl::make_shared>();
// evaluate if there is a collision for both paths
const bool has_collision =
has_collision_ego(filtered_objects) || has_collision_predicted(filtered_objects);
@@ -890,20 +897,17 @@ void AEB::addMarker(
"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";
+ closest_object_velocity_marker_array.text +=
+ "RSS distance: " + std::to_string(obj.rss) + " [m]";
debug_markers.markers.push_back(closest_object_velocity_marker_array);
}
}
-void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers)
+void AEB::addVirtualStopWallMarker(MarkerArray & markers)
{
- 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::TransformStamped tf_current_pose;
geometry_msgs::msg::Pose p;
@@ -928,10 +932,20 @@ void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_marker
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);
}
}
+void AEB::addCollisionMarker(const ObjectData & data, MarkerArray & debug_markers)
+{
+ 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);
+}
+
} // namespace autoware::motion::control::autonomous_emergency_braking
#include
diff --git a/control/autoware_autonomous_emergency_braking/src/utils.cpp b/control/autoware_autonomous_emergency_braking/src/utils.cpp
index f3b5192855d84..1b9fad6af9860 100644
--- a/control/autoware_autonomous_emergency_braking/src/utils.cpp
+++ b/control/autoware_autonomous_emergency_braking/src/utils.cpp
@@ -49,6 +49,9 @@ PredictedObject transformObjectFrame(
Polygon2d convertPolygonObjectToGeometryPolygon(
const Pose & current_pose, const autoware_perception_msgs::msg::Shape & obj_shape)
{
+ if (obj_shape.footprint.points.empty()) {
+ return {};
+ }
Polygon2d object_polygon;
tf2::Transform tf_map2obj;
fromMsg(current_pose, tf_map2obj);
diff --git a/control/autoware_autonomous_emergency_braking/test/test.cpp b/control/autoware_autonomous_emergency_braking/test/test.cpp
new file mode 100644
index 0000000000000..42054e718d09c
--- /dev/null
+++ b/control/autoware_autonomous_emergency_braking/test/test.cpp
@@ -0,0 +1,326 @@
+// Copyright 2024 TIER IV
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "test.hpp"
+
+#include "autoware/autonomous_emergency_braking/node.hpp"
+#include "autoware/universe_utils/geometry/geometry.hpp"
+
+#include
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+
+#include
+#include
+
+namespace autoware::motion::control::autonomous_emergency_braking::test
+{
+using autoware::universe_utils::Polygon2d;
+using autoware_perception_msgs::msg::PredictedObject;
+using autoware_perception_msgs::msg::PredictedObjects;
+using geometry_msgs::msg::Point;
+using geometry_msgs::msg::Pose;
+using geometry_msgs::msg::TransformStamped;
+using geometry_msgs::msg::Vector3;
+using std_msgs::msg::Header;
+
+Header get_header(const char * const frame_id, rclcpp::Time t)
+{
+ std_msgs::msg::Header header;
+ header.stamp = t;
+ header.frame_id = frame_id;
+ return header;
+};
+
+Imu make_imu_message(
+ const Header & header, const double ax, const double ay, const double yaw,
+ const double angular_velocity_z)
+{
+ Imu imu_msg;
+ imu_msg.header = header;
+ imu_msg.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw);
+ imu_msg.angular_velocity.z = angular_velocity_z;
+ imu_msg.linear_acceleration.x = ax;
+ imu_msg.linear_acceleration.y = ay;
+ return imu_msg;
+};
+
+VelocityReport make_velocity_report_msg(
+ const Header & header, const double lat_velocity, const double long_velocity,
+ const double heading_rate)
+{
+ VelocityReport velocity_msg;
+ velocity_msg.header = header;
+ velocity_msg.lateral_velocity = lat_velocity;
+ velocity_msg.longitudinal_velocity = long_velocity;
+ velocity_msg.heading_rate = heading_rate;
+ return velocity_msg;
+}
+
+std::shared_ptr generateNode()
+{
+ auto node_options = rclcpp::NodeOptions{};
+
+ const auto aeb_dir =
+ ament_index_cpp::get_package_share_directory("autoware_autonomous_emergency_braking");
+ const auto vehicle_info_util_dir =
+ ament_index_cpp::get_package_share_directory("autoware_vehicle_info_utils");
+
+ node_options.arguments(
+ {"--ros-args", "--params-file", aeb_dir + "/config/autonomous_emergency_braking.param.yaml",
+ "--ros-args", "--params-file", vehicle_info_util_dir + "/config/vehicle_info.param.yaml"});
+ return std::make_shared(node_options);
+};
+
+std::shared_ptr generatePubSubNode()
+{
+ auto node_options = rclcpp::NodeOptions{};
+ node_options.arguments({"--ros-args"});
+ return std::make_shared(node_options);
+};
+
+PubSubNode::PubSubNode(const rclcpp::NodeOptions & node_options)
+: Node("test_aeb_pubsub", node_options)
+{
+ rclcpp::QoS qos{1};
+ qos.transient_local();
+
+ pub_imu_ = create_publisher("~/input/imu", qos);
+ pub_point_cloud_ = create_publisher("~/input/pointcloud", qos);
+ pub_velocity_ = create_publisher("~/input/velocity", qos);
+ pub_predicted_traj_ = create_publisher("~/input/predicted_trajectory", qos);
+ pub_predicted_objects_ = create_publisher("~/input/objects", qos);
+ pub_autoware_state_ = create_publisher("autoware/state", qos);
+}
+
+TEST_F(TestAEB, checkCollision)
+{
+ constexpr double longitudinal_velocity = 3.0;
+ ObjectData object_collision;
+ object_collision.distance_to_object = 0.5;
+ object_collision.velocity = 0.1;
+ ASSERT_TRUE(aeb_node_->hasCollision(longitudinal_velocity, object_collision));
+
+ ObjectData object_no_collision;
+ object_no_collision.distance_to_object = 10.0;
+ object_no_collision.velocity = 0.1;
+ ASSERT_FALSE(aeb_node_->hasCollision(longitudinal_velocity, object_no_collision));
+}
+
+TEST_F(TestAEB, checkImuPathGeneration)
+{
+ constexpr double longitudinal_velocity = 3.0;
+ constexpr double yaw_rate = 0.05;
+ const auto imu_path = aeb_node_->generateEgoPath(longitudinal_velocity, yaw_rate);
+ ASSERT_FALSE(imu_path.empty());
+
+ const double dt = aeb_node_->imu_prediction_time_interval_;
+ const double horizon = aeb_node_->imu_prediction_time_horizon_;
+ ASSERT_TRUE(imu_path.size() >= static_cast(horizon / dt));
+
+ const auto footprint = aeb_node_->generatePathFootprint(imu_path, 0.0);
+ ASSERT_FALSE(footprint.empty());
+ ASSERT_TRUE(footprint.size() == imu_path.size() - 1);
+
+ const auto stamp = rclcpp::Time();
+ pcl::PointCloud::Ptr obstacle_points_ptr =
+ pcl::make_shared>();
+ {
+ const double x_start{0.0};
+ const double y_start{0.0};
+
+ for (size_t i = 0; i < 15; ++i) {
+ pcl::PointXYZ p1(
+ x_start + static_cast(i / 100.0), y_start - static_cast(i / 100.0), 0.5);
+ pcl::PointXYZ p2(
+ x_start + static_cast((i + 10) / 100.0), y_start - static_cast(i / 100.0),
+ 0.5);
+ obstacle_points_ptr->push_back(p1);
+ obstacle_points_ptr->push_back(p2);
+ }
+ }
+ std::vector objects;
+ aeb_node_->createObjectDataUsingPointCloudClusters(
+ imu_path, footprint, stamp, objects, obstacle_points_ptr);
+ ASSERT_FALSE(objects.empty());
+}
+
+TEST_F(TestAEB, checkIncompleteImuPathGeneration)
+{
+ const double dt = aeb_node_->imu_prediction_time_interval_;
+ const double horizon = aeb_node_->imu_prediction_time_horizon_;
+ const double min_generated_path_length = aeb_node_->min_generated_path_length_;
+ const double slow_velocity = min_generated_path_length / (2.0 * horizon);
+ constexpr double yaw_rate = 0.05;
+ const auto imu_path = aeb_node_->generateEgoPath(slow_velocity, yaw_rate);
+
+ ASSERT_FALSE(imu_path.empty());
+ ASSERT_TRUE(imu_path.size() >= static_cast(horizon / dt));
+ ASSERT_TRUE(autoware::motion_utils::calcArcLength(imu_path) >= min_generated_path_length);
+
+ const auto footprint = aeb_node_->generatePathFootprint(imu_path, 0.0);
+ ASSERT_FALSE(footprint.empty());
+ ASSERT_TRUE(footprint.size() == imu_path.size() - 1);
+}
+
+TEST_F(TestAEB, checkEmptyPathAtZeroSpeed)
+{
+ const double velocity = 0.0;
+ constexpr double yaw_rate = 0.0;
+ const auto imu_path = aeb_node_->generateEgoPath(velocity, yaw_rate);
+ ASSERT_EQ(imu_path.size(), 1);
+}
+
+TEST_F(TestAEB, checkParamUpdate)
+{
+ std::vector parameters{rclcpp::Parameter("param")};
+ const auto result = aeb_node_->onParameter(parameters);
+ ASSERT_TRUE(result.successful);
+}
+
+TEST_F(TestAEB, checkEmptyFetchData)
+{
+ ASSERT_FALSE(aeb_node_->fetchLatestData());
+}
+
+TEST_F(TestAEB, checkConvertObjectToPolygon)
+{
+ using autoware_perception_msgs::msg::Shape;
+ PredictedObject obj_cylinder;
+ obj_cylinder.shape.type = Shape::CYLINDER;
+ obj_cylinder.shape.dimensions.x = 1.0;
+ Pose obj_cylinder_pose;
+ obj_cylinder_pose.position.x = 1.0;
+ obj_cylinder_pose.position.y = 1.0;
+ obj_cylinder.kinematics.initial_pose_with_covariance.pose = obj_cylinder_pose;
+ const auto cylinder_polygon = utils::convertObjToPolygon(obj_cylinder);
+ ASSERT_FALSE(cylinder_polygon.outer().empty());
+
+ PredictedObject obj_box;
+ obj_box.shape.type = Shape::BOUNDING_BOX;
+ obj_box.shape.dimensions.x = 1.0;
+ obj_box.shape.dimensions.y = 2.0;
+ Pose obj_box_pose;
+ obj_box_pose.position.x = 1.0;
+ obj_box_pose.position.y = 1.0;
+ obj_box.kinematics.initial_pose_with_covariance.pose = obj_box_pose;
+ const auto box_polygon = utils::convertObjToPolygon(obj_box);
+ ASSERT_FALSE(box_polygon.outer().empty());
+
+ geometry_msgs::msg::TransformStamped tf_stamped;
+ geometry_msgs::msg::Transform transform;
+
+ constexpr double yaw{0.0};
+ transform.rotation = autoware::universe_utils::createQuaternionFromYaw(yaw);
+ geometry_msgs::msg::Vector3 translation;
+ translation.x = 1.0;
+ translation.y = 0.0;
+ translation.z = 0.0;
+ transform.translation = translation;
+ tf_stamped.set__transform(transform);
+ const auto t_obj_box = utils::transformObjectFrame(obj_box, tf_stamped);
+ const auto t_pose = t_obj_box.kinematics.initial_pose_with_covariance.pose;
+ Pose expected_pose;
+ expected_pose.position.x = obj_box_pose.position.x + translation.x;
+ expected_pose.position.y = obj_box_pose.position.y + translation.y;
+ expected_pose.position.z = obj_box_pose.position.z + translation.z;
+
+ ASSERT_DOUBLE_EQ(expected_pose.position.x, t_pose.position.x);
+ ASSERT_DOUBLE_EQ(expected_pose.position.y, t_pose.position.y);
+ ASSERT_DOUBLE_EQ(expected_pose.position.z, t_pose.position.z);
+}
+
+TEST_F(TestAEB, CollisionDataKeeper)
+{
+ using namespace std::literals::chrono_literals;
+ constexpr double collision_keeping_sec{1.0}, previous_obstacle_keep_time{1.0};
+ CollisionDataKeeper collision_data_keeper_(aeb_node_->get_clock());
+ collision_data_keeper_.setTimeout(collision_keeping_sec, previous_obstacle_keep_time);
+ ASSERT_TRUE(collision_data_keeper_.checkCollisionExpired());
+ ASSERT_TRUE(collision_data_keeper_.checkPreviousObjectDataExpired());
+
+ ObjectData obj;
+ obj.stamp = aeb_node_->now();
+ obj.velocity = 0.0;
+ obj.position.x = 0.0;
+ rclcpp::sleep_for(100ms);
+
+ ObjectData obj2;
+ obj2.stamp = aeb_node_->now();
+ obj2.velocity = 0.0;
+ obj2.position.x = 0.1;
+ rclcpp::sleep_for(100ms);
+
+ constexpr double ego_longitudinal_velocity = 3.0;
+ constexpr double yaw_rate = 0.0;
+ const auto imu_path = aeb_node_->generateEgoPath(ego_longitudinal_velocity, yaw_rate);
+
+ const auto speed_null =
+ collision_data_keeper_.calcObjectSpeedFromHistory(obj, imu_path, ego_longitudinal_velocity);
+ ASSERT_FALSE(speed_null.has_value());
+
+ const auto median_velocity =
+ collision_data_keeper_.calcObjectSpeedFromHistory(obj2, imu_path, ego_longitudinal_velocity);
+ ASSERT_TRUE(median_velocity.has_value());
+
+ // object speed is 1.0 m/s greater than ego's = 0.1 [m] / 0.1 [s] + longitudinal_velocity
+ ASSERT_TRUE(std::abs(median_velocity.value() - 4.0) < 1e-2);
+ rclcpp::sleep_for(1100ms);
+ ASSERT_TRUE(collision_data_keeper_.checkCollisionExpired());
+}
+
+TEST_F(TestAEB, TestCropPointCloud)
+{
+ constexpr double longitudinal_velocity = 3.0;
+ constexpr double yaw_rate = 0.05;
+ const auto imu_path = aeb_node_->generateEgoPath(longitudinal_velocity, yaw_rate);
+ ASSERT_FALSE(imu_path.empty());
+
+ constexpr size_t n_points{15};
+ // Create n_points inside the path and 1 point outside.
+ pcl::PointCloud::Ptr obstacle_points_ptr =
+ pcl::make_shared>();
+ {
+ constexpr double x_start{0.0};
+ constexpr double y_start{0.0};
+
+ for (size_t i = 0; i < n_points; ++i) {
+ const double offset_1 = static_cast(i / 100.0);
+ const double offset_2 = static_cast((i + 10) / 100.0);
+ pcl::PointXYZ p1(x_start + offset_1, y_start - offset_1, 0.5);
+ pcl::PointXYZ p2(x_start + offset_2, y_start - offset_1, 0.5);
+ obstacle_points_ptr->push_back(p1);
+ obstacle_points_ptr->push_back(p2);
+ }
+ pcl::PointXYZ p_out(x_start + 100.0, y_start + 100, 0.5);
+ obstacle_points_ptr->push_back(p_out);
+ }
+ aeb_node_->obstacle_ros_pointcloud_ptr_ = std::make_shared();
+ pcl::toROSMsg(*obstacle_points_ptr, *aeb_node_->obstacle_ros_pointcloud_ptr_);
+ const auto footprint = aeb_node_->generatePathFootprint(imu_path, 0.0);
+
+ pcl::PointCloud::Ptr filtered_objects =
+ pcl::make_shared>();
+ aeb_node_->cropPointCloudWithEgoFootprintPath(footprint, filtered_objects);
+ // Check if the point outside the path was excluded
+ ASSERT_TRUE(filtered_objects->points.size() == 2 * n_points);
+}
+
+} // namespace autoware::motion::control::autonomous_emergency_braking::test
diff --git a/control/autoware_autonomous_emergency_braking/test/test.hpp b/control/autoware_autonomous_emergency_braking/test/test.hpp
new file mode 100644
index 0000000000000..86edbf73a2a12
--- /dev/null
+++ b/control/autoware_autonomous_emergency_braking/test/test.hpp
@@ -0,0 +1,116 @@
+// Copyright 2024 TIER IV
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef TEST_HPP_
+#define TEST_HPP_
+
+#include "ament_index_cpp/get_package_share_directory.hpp"
+#include "autoware_test_utils/autoware_test_utils.hpp"
+#include "autoware_test_utils/mock_data_parser.hpp"
+#include "gtest/gtest.h"
+
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+namespace autoware::motion::control::autonomous_emergency_braking::test
+{
+using autoware_planning_msgs::msg::Trajectory;
+using autoware_system_msgs::msg::AutowareState;
+using autoware_vehicle_msgs::msg::VelocityReport;
+using nav_msgs::msg::Odometry;
+using sensor_msgs::msg::Imu;
+using sensor_msgs::msg::PointCloud2;
+using PointCloud = pcl::PointCloud;
+using autoware::universe_utils::Polygon2d;
+using autoware::vehicle_info_utils::VehicleInfo;
+using diagnostic_updater::DiagnosticStatusWrapper;
+using diagnostic_updater::Updater;
+using visualization_msgs::msg::Marker;
+using visualization_msgs::msg::MarkerArray;
+using Path = std::vector;
+using Vector3 = geometry_msgs::msg::Vector3;
+using autoware_perception_msgs::msg::PredictedObject;
+using autoware_perception_msgs::msg::PredictedObjects;
+using std_msgs::msg::Header;
+
+std::shared_ptr generateNode();
+Header get_header(const char * const frame_id, rclcpp::Time t);
+Imu make_imu_message(
+ const Header & header, const double ax, const double ay, const double yaw,
+ const double angular_velocity_z);
+VelocityReport make_velocity_report_msg(
+ const Header & header, const double lat_velocity, const double long_velocity,
+ const double heading_rate);
+class PubSubNode : public rclcpp::Node
+{
+public:
+ explicit PubSubNode(const rclcpp::NodeOptions & node_options);
+ // publisher
+ rclcpp::Publisher::SharedPtr pub_imu_;
+ rclcpp::Publisher::SharedPtr pub_point_cloud_;
+ rclcpp::Publisher::SharedPtr pub_velocity_;
+ rclcpp::Publisher::SharedPtr pub_predicted_traj_;
+ rclcpp::Publisher::SharedPtr pub_predicted_objects_;
+ rclcpp::Publisher::SharedPtr pub_autoware_state_;
+ // timer
+ // rclcpp::TimerBase::SharedPtr timer_;
+ void publishDefaultTopicsNoSpin()
+ {
+ const auto header = get_header("base_link", now());
+ const auto imu_msg = make_imu_message(header, 0.0, 0.0, 0.0, 0.05);
+ const auto velocity_msg = make_velocity_report_msg(header, 0.0, 3.0, 0.0);
+
+ pub_imu_->publish(imu_msg);
+ pub_velocity_->publish(velocity_msg);
+ };
+};
+
+std::shared_ptr generatePubSubNode();
+
+class TestAEB : public ::testing::Test
+{
+public:
+ TestAEB() {}
+ TestAEB(const TestAEB &) = delete;
+ TestAEB(TestAEB &&) = delete;
+ TestAEB & operator=(const TestAEB &) = delete;
+ TestAEB & operator=(TestAEB &&) = delete;
+ ~TestAEB() override = default;
+
+ void SetUp() override
+ {
+ rclcpp::init(0, nullptr);
+ pub_sub_node_ = generatePubSubNode();
+ aeb_node_ = generateNode();
+ }
+
+ void TearDown() override
+ {
+ aeb_node_.reset();
+ pub_sub_node_.reset();
+ rclcpp::shutdown();
+ }
+
+ std::shared_ptr pub_sub_node_;
+ std::shared_ptr aeb_node_;
+};
+} // namespace autoware::motion::control::autonomous_emergency_braking::test
+
+#endif // TEST_HPP_
diff --git a/control/autoware_control_validator/CMakeLists.txt b/control/autoware_control_validator/CMakeLists.txt
index 2b25b5b984c12..785fb8472ca5a 100644
--- a/control/autoware_control_validator/CMakeLists.txt
+++ b/control/autoware_control_validator/CMakeLists.txt
@@ -36,8 +36,13 @@ else()
target_link_libraries(autoware_control_validator_component "${cpp_typesupport_target}")
endif()
-# if(BUILD_TESTING)
-# endif()
+if(BUILD_TESTING)
+ file(GLOB_RECURSE TEST_SOURCES test/*.cpp)
+ ament_add_gtest(test_autoware_control_validator
+ ${TEST_SOURCES}
+ )
+ target_link_libraries(test_autoware_control_validator autoware_control_validator_component)
+endif()
ament_auto_package(
INSTALL_TO_SHARE
diff --git a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp
index 515f1c4cec339..56a1e39391b10 100644
--- a/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp
+++ b/control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp
@@ -17,18 +17,21 @@
#include "autoware/control_validator/debug_marker.hpp"
#include "autoware/universe_utils/ros/polling_subscriber.hpp"
-#include "autoware_control_validator/msg/control_validator_status.hpp"
-#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
+#include "autoware_vehicle_info_utils/vehicle_info.hpp"
+#include "diagnostic_updater/diagnostic_updater.hpp"
-#include
+#include
#include
#include
#include
#include
+#include
#include
#include
+#include
+#include
namespace autoware::control_validator
{
@@ -46,44 +49,103 @@ struct ValidationParams
double max_over_velocity_ratio_threshold;
};
+/**
+ * @class ControlValidator
+ * @brief Validates control commands by comparing predicted trajectories against reference
+ * trajectories.
+ */
class ControlValidator : public rclcpp::Node
{
public:
+ /**
+ * @brief Constructor
+ * @param options Node options
+ */
explicit ControlValidator(const rclcpp::NodeOptions & options);
- void onPredictedTrajectory(const Trajectory::ConstSharedPtr msg);
-
- bool checkValidMaxDistanceDeviation(const Trajectory & predicted_trajectory);
- bool checkValidVelocityDeviation(
- const Trajectory & reference_trajectory, const Odometry & kinematics);
+ /**
+ * @brief Callback function for the predicted trajectory.
+ * @param msg Predicted trajectory message
+ */
+ void on_predicted_trajectory(const Trajectory::ConstSharedPtr msg);
+
+ /**
+ * @brief Calculate the maximum lateral distance between the reference trajectory and predicted
+ * trajectory.
+ * @param predicted_trajectory Predicted trajectory
+ * @param reference_trajectory Reference trajectory
+ * @return A pair consisting of the maximum lateral deviation and a boolean indicating validity
+ */
+ std::pair calc_lateral_deviation_status(
+ const Trajectory & predicted_trajectory, const Trajectory & reference_trajectory) const;
+
+ /**
+ * @brief Calculate the velocity deviation between the reference trajectory and the current
+ * vehicle kinematics.
+ * @param reference_trajectory Reference trajectory
+ * @param kinematics Current vehicle kinematics
+ * @return A tuple containing the current velocity, desired velocity, and a boolean indicating
+ * validity
+ */
+ std::tuple calc_velocity_deviation_status(
+ const Trajectory & reference_trajectory, const Odometry & kinematics) const;
private:
- void setupDiag();
-
- void setupParameters();
-
- bool isDataReady();
-
+ /**
+ * @brief Setup diagnostic updater
+ */
+ void setup_diag();
+
+ /**
+ * @brief Setup parameters from the parameter server
+ */
+ void setup_parameters();
+
+ /**
+ * @brief Check if all required data is ready for validation
+ * @return Boolean indicating readiness of data
+ */
+ bool is_data_ready();
+
+ /**
+ * @brief Validate the predicted trajectory against the reference trajectory and current
+ * kinematics
+ * @param predicted_trajectory Predicted trajectory
+ * @param reference_trajectory Reference trajectory
+ * @param kinematics Current vehicle kinematics
+ */
void validate(
const Trajectory & predicted_trajectory, const Trajectory & reference_trajectory,
const Odometry & kinematics);
- void publishPredictedTrajectory();
- void publishDebugInfo();
- void displayStatus();
-
- void setStatus(DiagnosticStatusWrapper & stat, const bool & is_ok, const std::string & msg);
-
+ /**
+ * @brief Publish debug information
+ */
+ void publish_debug_info();
+
+ /**
+ * @brief Display validation status on terminal
+ */
+ void display_status();
+
+ /**
+ * @brief Set the diagnostic status
+ * @param stat Diagnostic status wrapper
+ * @param is_ok Boolean indicating if the status is okay
+ * @param msg Status message
+ */
+ void set_status(
+ DiagnosticStatusWrapper & stat, const bool & is_ok, const std::string & msg) const;
+
+ // Subscribers and publishers
rclcpp::Subscription::SharedPtr sub_predicted_traj_;
- autoware::universe_utils::InterProcessPollingSubscriber sub_kinematics_{
- this, "~/input/kinematics"};
- autoware::universe_utils::InterProcessPollingSubscriber sub_reference_traj_{
- this, "~/input/reference_trajectory"};
+ universe_utils::InterProcessPollingSubscriber::SharedPtr sub_kinematics_;
+ universe_utils::InterProcessPollingSubscriber::SharedPtr sub_reference_traj_;
rclcpp::Publisher::SharedPtr pub_status_;
rclcpp::Publisher::SharedPtr pub_markers_;
// system parameters
- int diag_error_count_threshold_ = 0;
+ int64_t diag_error_count_threshold_ = 0;
bool display_on_terminal_ = true;
Updater diag_updater_{this};
@@ -91,13 +153,14 @@ class ControlValidator : public rclcpp::Node
ControlValidatorStatus validation_status_;
ValidationParams validation_params_; // for thresholds
- // ego nearest index search
- double ego_nearest_dist_threshold_;
- double ego_nearest_yaw_threshold_;
-
- autoware::vehicle_info_utils::VehicleInfo vehicle_info_;
+ vehicle_info_utils::VehicleInfo vehicle_info_;
- bool isAllValid(const ControlValidatorStatus & status);
+ /**
+ * @brief Check if all validation criteria are met
+ * @param status Validation status
+ * @return Boolean indicating if all criteria are met
+ */
+ static bool is_all_valid(const ControlValidatorStatus & status);
Trajectory::ConstSharedPtr current_reference_trajectory_;
Trajectory::ConstSharedPtr current_predicted_trajectory_;
diff --git a/control/autoware_control_validator/include/autoware/control_validator/debug_marker.hpp b/control/autoware_control_validator/include/autoware/control_validator/debug_marker.hpp
index c03ecb46b8117..4c084ecbcc3e8 100644
--- a/control/autoware_control_validator/include/autoware/control_validator/debug_marker.hpp
+++ b/control/autoware_control_validator/include/autoware/control_validator/debug_marker.hpp
@@ -22,23 +22,41 @@
#include
#include
-## Setup
-
-After building autoware, move to `control/autoware_smart_mpc_trajectory_follower` and run the following command:
-
-```bash
-pip3 install .
-```
-
-If you have already installed and want to update the package, run the following command instead:
-
-```bash
-pip3 install -U .
-```
-
## Provided features
This package provides smart MPC logic for path-following control as well as mechanisms for learning and evaluation. These features are described below.
diff --git a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_NN.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_NN.py
index 84a0486b1e074..445897a4c580f 100644
--- a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_NN.py
+++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_NN.py
@@ -13,8 +13,8 @@
# limitations under the License.
+from autoware_smart_mpc_trajectory_follower import proxima_calc
from autoware_smart_mpc_trajectory_follower.scripts import drive_functions
-from autoware_smart_mpc_trajectory_follower.scripts import proxima_calc
import numpy as np
import torch
from torch import nn
diff --git a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_functions.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_functions.py
index 81ad4f8b38790..24773ed2d3e20 100644
--- a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_functions.py
+++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_functions.py
@@ -17,23 +17,21 @@
"""Define primary parameters and functions to be used elsewhere."""
from functools import partial
-import json
import os
from pathlib import Path
import sys
from typing import Callable
+from ament_index_python.packages import get_package_share_directory
from numba import njit
import numpy as np
import yaml
-package_path_json = str(Path(__file__).parent.parent) + "/package_path.json"
-with open(package_path_json, "r") as file:
- package_path = json.load(file)
+PACKAGE_NAME = "autoware_smart_mpc_trajectory_follower"
-mpc_param_path = (
- package_path["path"] + "/autoware_smart_mpc_trajectory_follower/param/mpc_param.yaml"
-)
+param_path = Path(get_package_share_directory(PACKAGE_NAME)) / "param"
+
+mpc_param_path = param_path / "mpc_param.yaml"
with open(mpc_param_path, "r") as yml:
mpc_param = yaml.safe_load(yml)
@@ -102,9 +100,7 @@
cap_pred_error = np.array(mpc_param["mpc_parameter"]["preprocessing"]["cap_pred_error"])
-nominal_param_path = (
- package_path["path"] + "/autoware_smart_mpc_trajectory_follower/param/nominal_param.yaml"
-)
+nominal_param_path = param_path / "nominal_param.yaml"
with open(nominal_param_path, "r") as yml:
nominal_param = yaml.safe_load(yml)
# Vehicle body information given by default.
@@ -173,10 +169,7 @@
)
max_error_steer = float(mpc_param["mpc_parameter"]["compensation"]["max_error_steer"])
-
-trained_model_param_path = (
- package_path["path"] + "/autoware_smart_mpc_trajectory_follower/param/trained_model_param.yaml"
-)
+trained_model_param_path = param_path / "trained_model_param.yaml"
with open(trained_model_param_path, "r") as yml:
trained_model_param = yaml.safe_load(yml)
use_trained_model_diff = bool(
@@ -370,31 +363,12 @@
)
# upper limit of input
-
-package_path_split = str(package_path["path"]).split("/")
-control_dir_path = ""
-for i in range(len(package_path_split)):
- control_dir_path += package_path_split[i]
- if package_path_split[i] == "control":
- break
- control_dir_path += "/"
-
read_limit_file = bool(mpc_param["mpc_parameter"]["limit"]["read_limit_file"])
if read_limit_file:
- limit_yaml_path = None
- for curDir, dirs, files in os.walk(control_dir_path):
- for name in files:
- if name == "vehicle_cmd_gate.param.yaml":
- if curDir.split("/")[-2] == "autoware_vehicle_cmd_gate":
- limit_yaml_path = curDir + "/" + name
- break
-
- limit_params = None
- if limit_yaml_path is not None:
- with open(limit_yaml_path, "r") as yml:
- limit_params = yaml.safe_load(yml)
- else:
- print("Error: limit_yaml_path is None")
+ limitter_package_path = Path(get_package_share_directory("autoware_vehicle_cmd_gate"))
+ limit_yaml_path = limitter_package_path / "config" / "vehicle_cmd_gate.param.yaml"
+ with open(limit_yaml_path, "r") as yml:
+ limit_params = yaml.safe_load(yml)
if limit_params is not None:
reference_speed_points = np.array(
diff --git a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.cpp b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/src/proxima_calc.cpp
similarity index 99%
rename from control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.cpp
rename to control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/src/proxima_calc.cpp
index 6dd39c72d433d..e96f27fee7e4d 100644
--- a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.cpp
+++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/src/proxima_calc.cpp
@@ -178,15 +178,15 @@ class transform_model_to_eigen
Eigen::VectorXd bias_linear_finalize_;
Eigen::MatrixXd A_linear_reg_;
Eigen::VectorXd b_linear_reg_;
- int deg_;
- int acc_delay_step_;
- int steer_delay_step_;
- int acc_ctrl_queue_size_;
- int steer_ctrl_queue_size_;
- int steer_ctrl_queue_size_core_;
- double vel_normalize_;
- double acc_normalize_;
- double steer_normalize_;
+ int deg_{};
+ int acc_delay_step_{};
+ int steer_delay_step_{};
+ int acc_ctrl_queue_size_{};
+ int steer_ctrl_queue_size_{};
+ int steer_ctrl_queue_size_core_{};
+ double vel_normalize_{};
+ double acc_normalize_{};
+ double steer_normalize_{};
static constexpr double max_acc_error_ = 20.0;
static constexpr double max_steer_error_ = 20.0;
@@ -611,15 +611,15 @@ class transform_model_with_memory_to_eigen
Eigen::VectorXd bias_linear_finalize_;
Eigen::MatrixXd A_linear_reg_;
Eigen::VectorXd b_linear_reg_;
- int deg_;
- int acc_delay_step_;
- int steer_delay_step_;
- int acc_ctrl_queue_size_;
- int steer_ctrl_queue_size_;
- int steer_ctrl_queue_size_core_;
- double vel_normalize_;
- double acc_normalize_;
- double steer_normalize_;
+ int deg_{};
+ int acc_delay_step_{};
+ int steer_delay_step_{};
+ int acc_ctrl_queue_size_{};
+ int steer_ctrl_queue_size_{};
+ int steer_ctrl_queue_size_core_{};
+ double vel_normalize_{};
+ double acc_normalize_{};
+ double steer_normalize_{};
static constexpr double max_acc_error_ = 20.0;
static constexpr double max_steer_error_ = 20.0;
diff --git a/control/autoware_smart_mpc_trajectory_follower/package.xml b/control/autoware_smart_mpc_trajectory_follower/package.xml
index 46ce55058a000..3fbe1bedc106e 100644
--- a/control/autoware_smart_mpc_trajectory_follower/package.xml
+++ b/control/autoware_smart_mpc_trajectory_follower/package.xml
@@ -25,9 +25,11 @@
autoware_planning_msgs
autoware_system_msgs
autoware_universe_utils
+ autoware_vehicle_cmd_gate
autoware_vehicle_msgs
pybind11_vendor
python3-scipy
+ python3-torch
rclcpp
rclcpp_components
diff --git a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py b/control/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py
similarity index 100%
rename from control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py
rename to control/autoware_smart_mpc_trajectory_follower/scripts/pympc_trajectory_follower.py
diff --git a/control/autoware_smart_mpc_trajectory_follower/setup.py b/control/autoware_smart_mpc_trajectory_follower/setup.py
deleted file mode 100644
index 22844b0f2d869..0000000000000
--- a/control/autoware_smart_mpc_trajectory_follower/setup.py
+++ /dev/null
@@ -1,42 +0,0 @@
-# cspell: ignore numba
-import glob
-import json
-from pathlib import Path
-import subprocess
-
-from setuptools import find_packages
-from setuptools import setup
-
-SKIP_PRE_INSTALL_FLAG = False
-
-if not SKIP_PRE_INSTALL_FLAG:
- subprocess.run("pip3 install numba==0.58.1 --force-reinstall", shell=True)
- subprocess.run("pip3 install pybind11", shell=True)
- subprocess.run("pip3 install GPy", shell=True)
- subprocess.run("pip3 install torch", shell=True)
- package_path = {}
- package_path["path"] = str(Path(__file__).parent)
- with open("autoware_smart_mpc_trajectory_follower/package_path.json", "w") as f:
- json.dump(package_path, f)
- build_cpp_command = (
- "g++ -Ofast -Wall -shared -std=c++11 -fPIC $(python3 -m pybind11 --includes) "
- )
- build_cpp_command += "autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.cpp "
- build_cpp_command += "-o autoware_smart_mpc_trajectory_follower/scripts/proxima_calc$(python3-config --extension-suffix) "
- build_cpp_command += "-lrt -I/usr/include/eigen3"
- subprocess.run(build_cpp_command, shell=True)
-
-so_path = (
- "scripts/"
- + glob.glob("autoware_smart_mpc_trajectory_follower/scripts/proxima_calc.*.so")[0].split("/")[
- -1
- ]
-)
-setup(
- name="autoware_smart_mpc_trajectory_follower",
- version="2.0.0",
- packages=find_packages(),
- package_data={
- "autoware_smart_mpc_trajectory_follower": ["package_path.json", so_path],
- },
-)
diff --git a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.cpp b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.cpp
index f14a62fba9661..a4bce3be35cb0 100644
--- a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.cpp
+++ b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.cpp
@@ -29,7 +29,7 @@ AdapiPauseInterface::AdapiPauseInterface(rclcpp::Node * node) : node_(node)
publish();
}
-bool AdapiPauseInterface::is_paused()
+bool AdapiPauseInterface::is_paused() const
{
return is_paused_;
}
diff --git a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp
index d75b544752e3f..6f3aa70bcea54 100644
--- a/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp
+++ b/control/autoware_vehicle_cmd_gate/src/adapi_pause_interface.hpp
@@ -35,7 +35,7 @@ class AdapiPauseInterface
public:
explicit AdapiPauseInterface(rclcpp::Node * node);
- bool is_paused();
+ bool is_paused() const;
void publish();
void update(const Control & control);
diff --git a/control/autoware_vehicle_cmd_gate/src/marker_helper.hpp b/control/autoware_vehicle_cmd_gate/src/marker_helper.hpp
index c9d7e86fa23dd..a2e357f6068a9 100644
--- a/control/autoware_vehicle_cmd_gate/src/marker_helper.hpp
+++ b/control/autoware_vehicle_cmd_gate/src/marker_helper.hpp
@@ -96,7 +96,7 @@ inline visualization_msgs::msg::Marker createMarker(
inline visualization_msgs::msg::Marker createStringMarker(
const std::string & frame_id, const std::string & ns, const int32_t id, const int32_t type,
geometry_msgs::msg::Point point, geometry_msgs::msg::Vector3 scale,
- const std_msgs::msg::ColorRGBA & color, const std::string text)
+ const std_msgs::msg::ColorRGBA & color, const std::string & text)
{
visualization_msgs::msg::Marker marker;
diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp
index cec23b05b8191..60845788adcf5 100644
--- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp
+++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp
@@ -20,7 +20,7 @@
namespace autoware::vehicle_cmd_gate
{
-VehicleCmdFilter::VehicleCmdFilter()
+VehicleCmdFilter::VehicleCmdFilter() : param_()
{
}
@@ -40,43 +40,43 @@ bool VehicleCmdFilter::setParameterWithValidation(const VehicleCmdFilterParam &
param_ = p;
return true;
}
-void VehicleCmdFilter::setSteerLim(LimitArray v)
+void VehicleCmdFilter::setSteerLim(const LimitArray & v)
{
auto tmp = param_;
tmp.steer_lim = v;
setParameterWithValidation(tmp);
}
-void VehicleCmdFilter::setSteerRateLim(LimitArray v)
+void VehicleCmdFilter::setSteerRateLim(const LimitArray & v)
{
auto tmp = param_;
tmp.steer_rate_lim = v;
setParameterWithValidation(tmp);
}
-void VehicleCmdFilter::setLonAccLim(LimitArray v)
+void VehicleCmdFilter::setLonAccLim(const LimitArray & v)
{
auto tmp = param_;
tmp.lon_acc_lim = v;
setParameterWithValidation(tmp);
}
-void VehicleCmdFilter::setLonJerkLim(LimitArray v)
+void VehicleCmdFilter::setLonJerkLim(const LimitArray & v)
{
auto tmp = param_;
tmp.lon_jerk_lim = v;
setParameterWithValidation(tmp);
}
-void VehicleCmdFilter::setLatAccLim(LimitArray v)
+void VehicleCmdFilter::setLatAccLim(const LimitArray & v)
{
auto tmp = param_;
tmp.lat_acc_lim = v;
setParameterWithValidation(tmp);
}
-void VehicleCmdFilter::setLatJerkLim(LimitArray v)
+void VehicleCmdFilter::setLatJerkLim(const LimitArray & v)
{
auto tmp = param_;
tmp.lat_jerk_lim = v;
setParameterWithValidation(tmp);
}
-void VehicleCmdFilter::setActualSteerDiffLim(LimitArray v)
+void VehicleCmdFilter::setActualSteerDiffLim(const LimitArray & v)
{
auto tmp = param_;
tmp.actual_steer_diff_lim = v;
@@ -252,8 +252,7 @@ double VehicleCmdFilter::calcLatAcc(const Control & cmd, const double v) const
return v * v * std::tan(cmd.lateral.steering_tire_angle) / param_.wheel_base;
}
-double VehicleCmdFilter::limitDiff(
- const double curr, const double prev, const double diff_lim) const
+double VehicleCmdFilter::limitDiff(const double curr, const double prev, const double diff_lim)
{
double diff = std::max(std::min(curr - prev, diff_lim), -diff_lim);
return prev + diff;
diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp
index 96663474f47a4..a4877692b6dac 100644
--- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp
+++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.hpp
@@ -49,13 +49,13 @@ class VehicleCmdFilter
void setWheelBase(double v) { param_.wheel_base = v; }
void setVelLim(double v) { param_.vel_lim = v; }
- void setSteerLim(LimitArray v);
- void setSteerRateLim(LimitArray v);
- void setLonAccLim(LimitArray v);
- void setLonJerkLim(LimitArray v);
- void setLatAccLim(LimitArray v);
- void setLatJerkLim(LimitArray v);
- void setActualSteerDiffLim(LimitArray v);
+ void setSteerLim(const LimitArray & v);
+ void setSteerRateLim(const LimitArray & v);
+ void setLonAccLim(const LimitArray & v);
+ void setLonJerkLim(const LimitArray & v);
+ void setLatAccLim(const LimitArray & v);
+ void setLatJerkLim(const LimitArray & v);
+ void setActualSteerDiffLim(const LimitArray & v);
void setCurrentSpeed(double v) { current_speed_ = v; }
void setParam(const VehicleCmdFilterParam & p);
VehicleCmdFilterParam getParam() const;
@@ -75,7 +75,7 @@ class VehicleCmdFilter
static IsFilterActivated checkIsActivated(
const Control & c1, const Control & c2, const double tol = 1.0e-3);
- Control getPrevCmd() { return prev_cmd_; }
+ Control getPrevCmd() const { return prev_cmd_; }
private:
VehicleCmdFilterParam param_;
@@ -87,7 +87,7 @@ class VehicleCmdFilter
double calcLatAcc(const Control & cmd) const;
double calcLatAcc(const Control & cmd, const double v) const;
double calcSteerFromLatacc(const double v, const double latacc) const;
- double limitDiff(const double curr, const double prev, const double diff_lim) const;
+ static double limitDiff(const double curr, const double prev, const double diff_lim);
double interpolateFromSpeed(const LimitArray & limits) const;
double getLonAccLim() const;
diff --git a/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp b/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp
index e17cfd98b27da..669afdd7229b0 100644
--- a/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp
+++ b/evaluator/autoware_planning_evaluator/src/metrics/metrics_utils.cpp
@@ -30,9 +30,8 @@ size_t getIndexAfterDistance(const Trajectory & traj, const size_t curr_id, cons
const TrajectoryPoint & curr_p = traj.points.at(curr_id);
size_t target_id = curr_id;
- double current_distance = 0.0;
for (size_t traj_id = curr_id + 1; traj_id < traj.points.size(); ++traj_id) {
- current_distance = calcDistance2d(traj.points.at(traj_id), curr_p);
+ double current_distance = calcDistance2d(traj.points.at(traj_id), curr_p);
if (current_distance >= distance) {
target_id = traj_id;
break;
diff --git a/launch/tier4_autoware_api_launch/launch/deprecated_api.launch.xml b/launch/tier4_autoware_api_launch/launch/deprecated_api.launch.xml
index 0856b9ca073cd..cdd1702fec70b 100644
--- a/launch/tier4_autoware_api_launch/launch/deprecated_api.launch.xml
+++ b/launch/tier4_autoware_api_launch/launch/deprecated_api.launch.xml
@@ -15,6 +15,6 @@
-
+
diff --git a/launch/tier4_autoware_api_launch/package.xml b/launch/tier4_autoware_api_launch/package.xml
index c55f1c8038e83..d45d21b3ed949 100644
--- a/launch/tier4_autoware_api_launch/package.xml
+++ b/launch/tier4_autoware_api_launch/package.xml
@@ -14,9 +14,9 @@
ad_api_adaptors
autoware_iv_external_api_adaptor
autoware_iv_internal_api_adaptor
+ autoware_path_distance_calculator
awapi_awiv_adapter
default_ad_api
- path_distance_calculator
rosbridge_server
topic_tools
diff --git a/launch/tier4_control_launch/launch/control.launch.xml b/launch/tier4_control_launch/launch/control.launch.xml
index f5582b7aeb305..0eda6faaf4e05 100644
--- a/launch/tier4_control_launch/launch/control.launch.xml
+++ b/launch/tier4_control_launch/launch/control.launch.xml
@@ -192,7 +192,6 @@
-
diff --git a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml
index b39346de8f8da..fa479c71dcbac 100644
--- a/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml
+++ b/launch/tier4_localization_launch/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml
@@ -26,7 +26,7 @@
-
+
diff --git a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py
index 79c99398966da..74b89e9298da4 100644
--- a/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py
+++ b/launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py
@@ -88,7 +88,7 @@ def create_parameter_dict(*args):
package="autoware_traffic_light_visualization",
plugin="autoware::traffic_light::TrafficLightRoiVisualizerNode",
name="traffic_light_roi_visualizer",
- parameters=[create_parameter_dict("enable_fine_detection")],
+ parameters=[create_parameter_dict("enable_fine_detection", "use_image_transport")],
remappings=[
("~/input/image", LaunchConfiguration("input/image")),
("~/input/rois", LaunchConfiguration("output/rois")),
@@ -172,6 +172,7 @@ def add_launch_arg(name: str, default_value=None, description=None):
classifier_share_dir = get_package_share_directory("autoware_traffic_light_classifier")
add_launch_arg("enable_image_decompressor", "True")
add_launch_arg("enable_fine_detection", "True")
+ add_launch_arg("use_image_transport", "True")
add_launch_arg("input/image", "/sensing/camera/traffic_light/image_raw")
add_launch_arg("output/rois", "/perception/traffic_light_recognition/rois")
add_launch_arg(
diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/README.md b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/README.md
index 14501c689dbe6..788f7bbc6b3a8 100644
--- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/README.md
+++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/README.md
@@ -32,7 +32,7 @@ The positions and orientations of the AR-Tags are assumed to be written in the L
## Parameters
-{{ json_to_markdown("localization/landmark_based_localizer/ar_tag_based_localizer/schema/ar_tag_based_localizer.schema.json") }}
+{{ json_to_markdown("localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/schema/ar_tag_based_localizer.schema.json") }}
## How to launch
diff --git a/localization/pose2twist/CMakeLists.txt b/localization/autoware_pose2twist/CMakeLists.txt
similarity index 77%
rename from localization/pose2twist/CMakeLists.txt
rename to localization/autoware_pose2twist/CMakeLists.txt
index ee63d9f43559a..2783e1a69047a 100644
--- a/localization/pose2twist/CMakeLists.txt
+++ b/localization/autoware_pose2twist/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
-project(pose2twist)
+project(autoware_pose2twist)
find_package(autoware_cmake REQUIRED)
autoware_package()
@@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
)
rclcpp_components_register_node(${PROJECT_NAME}
- PLUGIN "Pose2Twist"
+ PLUGIN "autoware::pose2twist::Pose2Twist"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)
@@ -19,6 +19,9 @@ if(BUILD_TESTING)
ament_auto_add_gtest(test_angular_velocity
test/test_angular_velocity.cpp
)
+ target_include_directories(test_angular_velocity PRIVATE
+ src
+ )
endif()
ament_auto_package(
diff --git a/localization/pose2twist/README.md b/localization/autoware_pose2twist/README.md
similarity index 82%
rename from localization/pose2twist/README.md
rename to localization/autoware_pose2twist/README.md
index f1f7d6408fafb..55ca4667c423d 100644
--- a/localization/pose2twist/README.md
+++ b/localization/autoware_pose2twist/README.md
@@ -1,8 +1,8 @@
-# pose2twist
+# autoware_pose2twist
## Purpose
-This `pose2twist` calculates the velocity from the input pose history. In addition to the computed twist, this node outputs the linear-x and angular-z components as a float message to simplify debugging.
+This `autoware_pose2twist` calculates the velocity from the input pose history. In addition to the computed twist, this node outputs the linear-x and angular-z components as a float message to simplify debugging.
The `twist.linear.x` is calculated as `sqrt(dx * dx + dy * dy + dz * dz) / dt`, and the values in the `y` and `z` fields are zero.
The `twist.angular` is calculated as `relative_rotation_vector / dt` for each field.
diff --git a/localization/pose2twist/launch/pose2twist.launch.xml b/localization/autoware_pose2twist/launch/pose2twist.launch.xml
similarity index 79%
rename from localization/pose2twist/launch/pose2twist.launch.xml
rename to localization/autoware_pose2twist/launch/pose2twist.launch.xml
index 57a41dbfcf017..8ac802a5d0ce3 100644
--- a/localization/pose2twist/launch/pose2twist.launch.xml
+++ b/localization/autoware_pose2twist/launch/pose2twist.launch.xml
@@ -2,7 +2,7 @@
-
+
diff --git a/localization/pose2twist/package.xml b/localization/autoware_pose2twist/package.xml
similarity index 92%
rename from localization/pose2twist/package.xml
rename to localization/autoware_pose2twist/package.xml
index 07e445c72978c..dc499f8eda5a4 100644
--- a/localization/pose2twist/package.xml
+++ b/localization/autoware_pose2twist/package.xml
@@ -1,9 +1,9 @@
- pose2twist
+ autoware_pose2twist
0.1.0
- The pose2twist package
+ The autoware_pose2twist package
Yamato Ando
Masahiro Sakamoto
Kento Yabuuchi
diff --git a/localization/pose2twist/src/pose2twist_core.cpp b/localization/autoware_pose2twist/src/pose2twist_core.cpp
similarity index 96%
rename from localization/pose2twist/src/pose2twist_core.cpp
rename to localization/autoware_pose2twist/src/pose2twist_core.cpp
index cdde78ed7e357..4dc7b5fb04209 100644
--- a/localization/pose2twist/src/pose2twist_core.cpp
+++ b/localization/autoware_pose2twist/src/pose2twist_core.cpp
@@ -12,12 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "pose2twist/pose2twist_core.hpp"
+#include "pose2twist_core.hpp"
#include
#include
#include
+namespace autoware::pose2twist
+{
Pose2Twist::Pose2Twist(const rclcpp::NodeOptions & options) : rclcpp::Node("pose2twist", options)
{
using std::placeholders::_1;
@@ -113,6 +115,7 @@ void Pose2Twist::callback_pose(geometry_msgs::msg::PoseStamped::SharedPtr pose_m
angular_z_msg.data = static_cast(twist_msg.twist.angular.z);
angular_z_pub_->publish(angular_z_msg);
}
+} // namespace autoware::pose2twist
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(Pose2Twist)
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pose2twist::Pose2Twist)
diff --git a/localization/pose2twist/include/pose2twist/pose2twist_core.hpp b/localization/autoware_pose2twist/src/pose2twist_core.hpp
similarity index 91%
rename from localization/pose2twist/include/pose2twist/pose2twist_core.hpp
rename to localization/autoware_pose2twist/src/pose2twist_core.hpp
index d1ff6ee5ff8b6..ed3e542beb857 100644
--- a/localization/pose2twist/include/pose2twist/pose2twist_core.hpp
+++ b/localization/autoware_pose2twist/src/pose2twist_core.hpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef POSE2TWIST__POSE2TWIST_CORE_HPP_
-#define POSE2TWIST__POSE2TWIST_CORE_HPP_
+#ifndef POSE2TWIST_CORE_HPP_
+#define POSE2TWIST_CORE_HPP_
#include
@@ -27,6 +27,8 @@
#include
#endif
+namespace autoware::pose2twist
+{
// Compute the relative rotation of q2 from q1 as a rotation vector
geometry_msgs::msg::Vector3 compute_relative_rotation_vector(
const tf2::Quaternion & q1, const tf2::Quaternion & q2);
@@ -45,5 +47,6 @@ class Pose2Twist : public rclcpp::Node
rclcpp::Publisher::SharedPtr linear_x_pub_;
rclcpp::Publisher::SharedPtr angular_z_pub_;
};
+} // namespace autoware::pose2twist
-#endif // POSE2TWIST__POSE2TWIST_CORE_HPP_
+#endif // POSE2TWIST_CORE_HPP_
diff --git a/localization/pose2twist/test/test_angular_velocity.cpp b/localization/autoware_pose2twist/test/test_angular_velocity.cpp
similarity index 97%
rename from localization/pose2twist/test/test_angular_velocity.cpp
rename to localization/autoware_pose2twist/test/test_angular_velocity.cpp
index bf2ca0a3ba5c2..38eba6f329565 100644
--- a/localization/pose2twist/test/test_angular_velocity.cpp
+++ b/localization/autoware_pose2twist/test/test_angular_velocity.cpp
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "pose2twist/pose2twist_core.hpp"
+#include "pose2twist_core.hpp"
#include
@@ -102,7 +102,7 @@ TEST(AngularVelocityFromQuaternion, CheckNumericalValidity)
// Calculate the relative rotation between the initial and final quaternion
const geometry_msgs::msg::Vector3 rotation_vector =
- compute_relative_rotation_vector(initial_q, final_q);
+ autoware::pose2twist::compute_relative_rotation_vector(initial_q, final_q);
EXPECT_NEAR(rotation_vector.x, expected_axis.x() * expected_angle, acceptable_error);
EXPECT_NEAR(rotation_vector.y, expected_axis.y() * expected_angle, acceptable_error);
diff --git a/localization/autoware_stop_filter/README.md b/localization/autoware_stop_filter/README.md
index 261b8c9da392c..9904707a59996 100644
--- a/localization/autoware_stop_filter/README.md
+++ b/localization/autoware_stop_filter/README.md
@@ -25,4 +25,4 @@ This node aims to:
## Parameters
-{{ json_to_markdown("localization/stop_filter/schema/stop_filter.schema.json") }}
+{{ json_to_markdown("localization/autoware_stop_filter/schema/stop_filter.schema.json") }}
diff --git a/localization/twist2accel/CMakeLists.txt b/localization/autoware_twist2accel/CMakeLists.txt
similarity index 81%
rename from localization/twist2accel/CMakeLists.txt
rename to localization/autoware_twist2accel/CMakeLists.txt
index 9178bf02288a8..c5e3aadfb7fe0 100644
--- a/localization/twist2accel/CMakeLists.txt
+++ b/localization/autoware_twist2accel/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
-project(twist2accel)
+project(autoware_twist2accel)
find_package(autoware_cmake REQUIRED)
autoware_package()
@@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
)
rclcpp_components_register_node(${PROJECT_NAME}
- PLUGIN "Twist2Accel"
+ PLUGIN "autoware::twist2accel::Twist2Accel"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)
diff --git a/localization/twist2accel/README.md b/localization/autoware_twist2accel/README.md
similarity index 89%
rename from localization/twist2accel/README.md
rename to localization/autoware_twist2accel/README.md
index 5a540dca895d4..4bdf29947e0e7 100644
--- a/localization/twist2accel/README.md
+++ b/localization/autoware_twist2accel/README.md
@@ -1,4 +1,4 @@
-# twist2accel
+# autoware_twist2accel
## Purpose
@@ -21,7 +21,7 @@ This package is responsible for estimating acceleration using the output of `ekf
## Parameters
-{{ json_to_markdown("localization/twist2accel/schema/twist2accel.schema.json") }}
+{{ json_to_markdown("localization/autoware_twist2accel/schema/twist2accel.schema.json") }}
## Future work
diff --git a/localization/twist2accel/config/twist2accel.param.yaml b/localization/autoware_twist2accel/config/twist2accel.param.yaml
similarity index 100%
rename from localization/twist2accel/config/twist2accel.param.yaml
rename to localization/autoware_twist2accel/config/twist2accel.param.yaml
diff --git a/localization/twist2accel/launch/twist2accel.launch.xml b/localization/autoware_twist2accel/launch/twist2accel.launch.xml
similarity index 65%
rename from localization/twist2accel/launch/twist2accel.launch.xml
rename to localization/autoware_twist2accel/launch/twist2accel.launch.xml
index c534a288aac3e..6fe10a8c80c32 100644
--- a/localization/twist2accel/launch/twist2accel.launch.xml
+++ b/localization/autoware_twist2accel/launch/twist2accel.launch.xml
@@ -1,10 +1,10 @@
-
+
-
+
diff --git a/localization/twist2accel/package.xml b/localization/autoware_twist2accel/package.xml
similarity index 97%
rename from localization/twist2accel/package.xml
rename to localization/autoware_twist2accel/package.xml
index 158d8a8a8d283..af8938fd74a9f 100644
--- a/localization/twist2accel/package.xml
+++ b/localization/autoware_twist2accel/package.xml
@@ -1,7 +1,7 @@
- twist2accel
+ autoware_twist2accel
0.0.0
The acceleration estimation package
Yamato Ando
diff --git a/localization/twist2accel/schema/twist2accel.schema.json b/localization/autoware_twist2accel/schema/twist2accel.schema.json
similarity index 100%
rename from localization/twist2accel/schema/twist2accel.schema.json
rename to localization/autoware_twist2accel/schema/twist2accel.schema.json
diff --git a/localization/twist2accel/src/twist2accel.cpp b/localization/autoware_twist2accel/src/twist2accel.cpp
similarity index 96%
rename from localization/twist2accel/src/twist2accel.cpp
rename to localization/autoware_twist2accel/src/twist2accel.cpp
index 800d696b1dea8..2205a9d3a674e 100644
--- a/localization/twist2accel/src/twist2accel.cpp
+++ b/localization/autoware_twist2accel/src/twist2accel.cpp
@@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include "twist2accel/twist2accel.hpp"
+#include "twist2accel.hpp"
#include
@@ -22,6 +22,8 @@
#include
#include
+namespace autoware::twist2accel
+{
using std::placeholders::_1;
Twist2Accel::Twist2Accel(const rclcpp::NodeOptions & node_options)
@@ -103,6 +105,7 @@ void Twist2Accel::estimate_accel(const geometry_msgs::msg::TwistStamped::SharedP
pub_accel_->publish(accel_msg);
prev_twist_ptr_ = msg;
}
+} // namespace autoware::twist2accel
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(Twist2Accel)
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::twist2accel::Twist2Accel)
diff --git a/localization/twist2accel/include/twist2accel/twist2accel.hpp b/localization/autoware_twist2accel/src/twist2accel.hpp
similarity index 91%
rename from localization/twist2accel/include/twist2accel/twist2accel.hpp
rename to localization/autoware_twist2accel/src/twist2accel.hpp
index e2fab219b11b4..97060c080179b 100644
--- a/localization/twist2accel/include/twist2accel/twist2accel.hpp
+++ b/localization/autoware_twist2accel/src/twist2accel.hpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef TWIST2ACCEL__TWIST2ACCEL_HPP_
-#define TWIST2ACCEL__TWIST2ACCEL_HPP_
+#ifndef TWIST2ACCEL_HPP_
+#define TWIST2ACCEL_HPP_
#include "signal_processing/lowpass_filter_1d.hpp"
@@ -37,10 +37,12 @@
#include
#include
+namespace autoware::twist2accel
+{
class Twist2Accel : public rclcpp::Node
{
public:
- explicit Twist2Accel(const rclcpp::NodeOptions & options);
+ explicit Twist2Accel(const rclcpp::NodeOptions & node_options);
private:
rclcpp::Publisher::SharedPtr
@@ -68,4 +70,5 @@ class Twist2Accel : public rclcpp::Node
void callback_odometry(const nav_msgs::msg::Odometry::SharedPtr msg);
void estimate_accel(const geometry_msgs::msg::TwistStamped::SharedPtr msg);
};
-#endif // TWIST2ACCEL__TWIST2ACCEL_HPP_
+} // namespace autoware::twist2accel
+#endif // TWIST2ACCEL_HPP_
diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp
index ada9024faceee..0b3f64caabe41 100644
--- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp
+++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp
@@ -239,6 +239,11 @@ class EKFLocalizer : public rclcpp::Node
autoware::universe_utils::StopWatch stop_watch_;
+ /**
+ * @brief last angular velocity for compensating rph with delay
+ */
+ tf2::Vector3 last_angular_velocity_;
+
friend class EKFLocalizerTestSuite; // for test code
};
#endif // EKF_LOCALIZER__EKF_LOCALIZER_HPP_
diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp
index ee360e798f492..5eda1156327b5 100644
--- a/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp
+++ b/localization/ekf_localizer/include/ekf_localizer/ekf_module.hpp
@@ -29,6 +29,8 @@
#include
#include
+#include
+
#include
#include
@@ -77,8 +79,8 @@ class EKFModule
bool measurement_update_twist(
const TwistWithCovariance & twist, const rclcpp::Time & t_curr,
EKFDiagnosticInfo & twist_diag_info);
- geometry_msgs::msg::PoseWithCovarianceStamped compensate_pose_with_z_delay(
- const PoseWithCovariance & pose, const double delay_time);
+ geometry_msgs::msg::PoseWithCovarianceStamped compensate_rph_with_delay(
+ const PoseWithCovariance & pose, tf2::Vector3 last_angular_velocity, const double delay_time);
private:
TimeDelayKalmanFilter kalman_filter_;
diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp
index e541939026d95..37880f4e4139a 100644
--- a/localization/ekf_localizer/src/ekf_localizer.cpp
+++ b/localization/ekf_localizer/src/ekf_localizer.cpp
@@ -47,7 +47,8 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options)
params_(this),
ekf_dt_(params_.ekf_dt),
pose_queue_(params_.pose_smoothing_steps),
- twist_queue_(params_.twist_smoothing_steps)
+ twist_queue_(params_.twist_smoothing_steps),
+ last_angular_velocity_(0.0, 0.0, 0.0)
{
/* convert to continuous to discrete */
proc_cov_vx_d_ = std::pow(params_.proc_stddev_vx_c * ekf_dt_, 2.0);
@@ -187,11 +188,13 @@ void EKFLocalizer::timer_callback()
if (is_updated) {
pose_is_updated = true;
- // Update Simple 1D filter with considering change of z value due to measurement pose delay
+ // Update Simple 1D filter with considering change of roll, pitch and height (position z)
+ // values due to measurement pose delay
const double delay_time =
(current_time - pose->header.stamp).seconds() + params_.pose_additional_delay;
- const auto pose_with_z_delay = ekf_module_->compensate_pose_with_z_delay(*pose, delay_time);
- update_simple_1d_filters(pose_with_z_delay, params_.pose_smoothing_steps);
+ auto pose_with_rph_delay_compensation =
+ ekf_module_->compensate_rph_with_delay(*pose, last_angular_velocity_, delay_time);
+ update_simple_1d_filters(pose_with_rph_delay_compensation, params_.pose_smoothing_steps);
}
}
DEBUG_INFO(
@@ -222,6 +225,10 @@ void EKFLocalizer::timer_callback()
ekf_module_->measurement_update_twist(*twist, current_time, twist_diag_info_);
if (is_updated) {
twist_is_updated = true;
+ last_angular_velocity_ = tf2::Vector3(
+ twist->twist.twist.angular.x, twist->twist.twist.angular.y, twist->twist.twist.angular.z);
+ } else {
+ last_angular_velocity_ = tf2::Vector3(0.0, 0.0, 0.0);
}
}
DEBUG_INFO(
diff --git a/localization/ekf_localizer/src/ekf_module.cpp b/localization/ekf_localizer/src/ekf_module.cpp
index ba6b7dedca82c..5c804afdc8cda 100644
--- a/localization/ekf_localizer/src/ekf_module.cpp
+++ b/localization/ekf_localizer/src/ekf_module.cpp
@@ -282,15 +282,39 @@ bool EKFModule::measurement_update_pose(
return true;
}
-geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensate_pose_with_z_delay(
- const PoseWithCovariance & pose, const double delay_time)
+geometry_msgs::msg::PoseWithCovarianceStamped EKFModule::compensate_rph_with_delay(
+ const PoseWithCovariance & pose, tf2::Vector3 last_angular_velocity, const double delay_time)
{
- const auto rpy = autoware::universe_utils::getRPY(pose.pose.pose.orientation);
- const double dz_delay = kalman_filter_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y);
- PoseWithCovariance pose_with_z_delay;
- pose_with_z_delay = pose;
- pose_with_z_delay.pose.pose.position.z += dz_delay;
- return pose_with_z_delay;
+ tf2::Quaternion delta_orientation;
+ if (last_angular_velocity.length() > 0.0) {
+ delta_orientation.setRotation(
+ last_angular_velocity.normalized(), last_angular_velocity.length() * delay_time);
+ } else {
+ delta_orientation.setValue(0.0, 0.0, 0.0, 1.0);
+ }
+
+ tf2::Quaternion prev_orientation = tf2::Quaternion(
+ pose.pose.pose.orientation.x, pose.pose.pose.orientation.y, pose.pose.pose.orientation.z,
+ pose.pose.pose.orientation.w);
+
+ tf2::Quaternion curr_orientation;
+ curr_orientation = prev_orientation * delta_orientation;
+ curr_orientation.normalize();
+
+ PoseWithCovariance pose_with_delay;
+ pose_with_delay = pose;
+ pose_with_delay.header.stamp =
+ rclcpp::Time(pose.header.stamp) + rclcpp::Duration::from_seconds(delay_time);
+ pose_with_delay.pose.pose.orientation.x = curr_orientation.x();
+ pose_with_delay.pose.pose.orientation.y = curr_orientation.y();
+ pose_with_delay.pose.pose.orientation.z = curr_orientation.z();
+ pose_with_delay.pose.pose.orientation.w = curr_orientation.w();
+
+ const auto rpy = autoware::universe_utils::getRPY(pose_with_delay.pose.pose.orientation);
+ const double delta_z = kalman_filter_.getXelement(IDX::VX) * delay_time * std::sin(-rpy.y);
+ pose_with_delay.pose.pose.position.z += delta_z;
+
+ return pose_with_delay;
}
bool EKFModule::measurement_update_twist(
diff --git a/localization/gyro_odometer/CMakeLists.txt b/localization/gyro_odometer/CMakeLists.txt
index 1b142b254d2e1..a832383ff4761 100644
--- a/localization/gyro_odometer/CMakeLists.txt
+++ b/localization/gyro_odometer/CMakeLists.txt
@@ -6,7 +6,6 @@ autoware_package()
ament_auto_add_library(${PROJECT_NAME} SHARED
src/gyro_odometer_core.cpp
- src/diagnostics_module.cpp
)
target_link_libraries(${PROJECT_NAME} fmt)
diff --git a/localization/gyro_odometer/include/gyro_odometer/diagnostics_module.hpp b/localization/gyro_odometer/include/gyro_odometer/diagnostics_module.hpp
deleted file mode 100644
index c5b7b7a592013..0000000000000
--- a/localization/gyro_odometer/include/gyro_odometer/diagnostics_module.hpp
+++ /dev/null
@@ -1,65 +0,0 @@
-// Copyright 2023 Autoware Foundation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef GYRO_ODOMETER__DIAGNOSTICS_MODULE_HPP_
-#define GYRO_ODOMETER__DIAGNOSTICS_MODULE_HPP_
-
-#include
-
-#include
-
-#include
-#include
-
-namespace autoware::gyro_odometer
-{
-
-class DiagnosticsModule
-{
-public:
- DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name);
- void clear();
- void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg);
- template
- void add_key_value(const std::string & key, const T & value);
- void update_level_and_message(const int8_t level, const std::string & message);
- void publish(const rclcpp::Time & publish_time_stamp);
-
-private:
- [[nodiscard]] diagnostic_msgs::msg::DiagnosticArray create_diagnostics_array(
- const rclcpp::Time & publish_time_stamp) const;
-
- rclcpp::Clock::SharedPtr clock_;
- rclcpp::Publisher::SharedPtr diagnostics_pub_;
-
- diagnostic_msgs::msg::DiagnosticStatus diagnostics_status_msg_;
-};
-
-template
-void DiagnosticsModule::add_key_value(const std::string & key, const T & value)
-{
- diagnostic_msgs::msg::KeyValue key_value;
- key_value.key = key;
- key_value.value = std::to_string(value);
- add_key_value(key_value);
-}
-
-template <>
-void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value);
-template <>
-void DiagnosticsModule::add_key_value(const std::string & key, const bool & value);
-
-} // namespace autoware::gyro_odometer
-
-#endif // GYRO_ODOMETER__DIAGNOSTICS_MODULE_HPP_
diff --git a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp
index f1f7214c3b848..f569ed25a0c7f 100644
--- a/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp
+++ b/localization/gyro_odometer/include/gyro_odometer/gyro_odometer_core.hpp
@@ -18,7 +18,7 @@
#include "autoware/universe_utils/ros/logger_level_configure.hpp"
#include "autoware/universe_utils/ros/msg_covariance.hpp"
#include "autoware/universe_utils/ros/transform_listener.hpp"
-#include "gyro_odometer/diagnostics_module.hpp"
+#include "localization_util/diagnostics_module.hpp"
#include
diff --git a/localization/gyro_odometer/package.xml b/localization/gyro_odometer/package.xml
index faa64a1313ebb..ba08a8852eca5 100644
--- a/localization/gyro_odometer/package.xml
+++ b/localization/gyro_odometer/package.xml
@@ -21,6 +21,7 @@
diagnostic_msgs
fmt
geometry_msgs
+ localization_util
rclcpp
rclcpp_components
sensor_msgs
diff --git a/localization/gyro_odometer/src/diagnostics_module.cpp b/localization/gyro_odometer/src/diagnostics_module.cpp
deleted file mode 100644
index 5d687943cef53..0000000000000
--- a/localization/gyro_odometer/src/diagnostics_module.cpp
+++ /dev/null
@@ -1,110 +0,0 @@
-// Copyright 2023 Autoware Foundation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#include "gyro_odometer/diagnostics_module.hpp"
-
-#include
-
-#include
-
-#include
-#include
-
-namespace autoware::gyro_odometer
-{
-
-DiagnosticsModule::DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name)
-: clock_(node->get_clock())
-{
- diagnostics_pub_ =
- node->create_publisher("/diagnostics", 10);
-
- diagnostics_status_msg_.name =
- std::string(node->get_name()) + std::string(": ") + diagnostic_name;
- diagnostics_status_msg_.hardware_id = node->get_name();
-}
-
-void DiagnosticsModule::clear()
-{
- diagnostics_status_msg_.values.clear();
- diagnostics_status_msg_.values.shrink_to_fit();
-
- diagnostics_status_msg_.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
- diagnostics_status_msg_.message = "";
-}
-
-void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg)
-{
- auto it = std::find_if(
- std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values),
- [key_value_msg](const auto & arg) { return arg.key == key_value_msg.key; });
-
- if (it != std::cend(diagnostics_status_msg_.values)) {
- it->value = key_value_msg.value;
- } else {
- diagnostics_status_msg_.values.push_back(key_value_msg);
- }
-}
-
-template <>
-void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value)
-{
- diagnostic_msgs::msg::KeyValue key_value;
- key_value.key = key;
- key_value.value = value;
- add_key_value(key_value);
-}
-
-template <>
-void DiagnosticsModule::add_key_value(const std::string & key, const bool & value)
-{
- diagnostic_msgs::msg::KeyValue key_value;
- key_value.key = key;
- key_value.value = value ? "True" : "False";
- add_key_value(key_value);
-}
-
-void DiagnosticsModule::update_level_and_message(const int8_t level, const std::string & message)
-{
- if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) {
- if (!diagnostics_status_msg_.message.empty()) {
- diagnostics_status_msg_.message += "; ";
- }
- diagnostics_status_msg_.message += message;
- }
- if (level > diagnostics_status_msg_.level) {
- diagnostics_status_msg_.level = level;
- }
-}
-
-void DiagnosticsModule::publish(const rclcpp::Time & publish_time_stamp)
-{
- diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp));
-}
-
-diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_array(
- const rclcpp::Time & publish_time_stamp) const
-{
- diagnostic_msgs::msg::DiagnosticArray diagnostics_msg;
- diagnostics_msg.header.stamp = publish_time_stamp;
- diagnostics_msg.status.push_back(diagnostics_status_msg_);
-
- if (diagnostics_msg.status.at(0).level == diagnostic_msgs::msg::DiagnosticStatus::OK) {
- diagnostics_msg.status.at(0).message = "OK";
- }
-
- return diagnostics_msg;
-}
-
-} // namespace autoware::gyro_odometer
diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
index d64107b03ebba..a90ec30aa91ff 100644
--- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
+++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
@@ -834,7 +834,7 @@ Eigen::Matrix2d NDTScanMatcher::estimate_covariance(
if (
param_.covariance.covariance_estimation.covariance_estimation_type ==
CovarianceEstimationType::LAPLACE_APPROXIMATION) {
- return pclomp::estimate_xy_covariance_by_Laplace_approximation(ndt_result.hessian);
+ return pclomp::estimate_xy_covariance_by_laplace_approximation(ndt_result.hessian);
} else if (
param_.covariance.covariance_estimation.covariance_estimation_type ==
CovarianceEstimationType::MULTI_NDT) {
diff --git a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp
index b011799e5b912..4e3728be53171 100644
--- a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp
+++ b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp
@@ -32,8 +32,7 @@ VoxelGridMapLoader::VoxelGridMapLoader(
}
bool VoxelGridMapLoader::is_close_points(
- const pcl::PointXYZ point, const pcl::PointXYZ target_point,
- const double distance_threshold) const
+ const pcl::PointXYZ point, const pcl::PointXYZ target_point, const double distance_threshold)
{
if (distance3D(point, target_point) < distance_threshold * distance_threshold) {
return true;
@@ -52,7 +51,7 @@ void VoxelGridMapLoader::publish_downsampled_map(
bool VoxelGridMapLoader::is_close_to_neighbor_voxels(
const pcl::PointXYZ & point, const double distance_threshold, VoxelGridPointXYZ & voxel,
- pcl::search::Search::Ptr tree) const
+ pcl::search::Search::Ptr tree)
{
const int index = voxel.getCentroidIndexAt(voxel.getGridCoordinates(point.x, point.y, point.z));
if (index != -1) {
diff --git a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp
index 07ed0aa7b92db..6560ae82f8bce 100644
--- a/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp
+++ b/perception/autoware_compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp
@@ -97,7 +97,7 @@ class VoxelGridMapLoader
rclcpp::Logger logger_;
std::mutex * mutex_ptr_;
double voxel_leaf_size_;
- double voxel_leaf_size_z_;
+ double voxel_leaf_size_z_{};
double downsize_ratio_z_axis_;
rclcpp::Publisher::SharedPtr downsampled_map_pub_;
bool debug_ = false;
@@ -111,9 +111,9 @@ class VoxelGridMapLoader
std::string * tf_map_input_frame, std::mutex * mutex);
virtual bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) = 0;
- bool is_close_to_neighbor_voxels(
+ static bool is_close_to_neighbor_voxels(
const pcl::PointXYZ & point, const double distance_threshold, VoxelGridPointXYZ & voxel,
- pcl::search::Search::Ptr tree) const;
+ pcl::search::Search::Ptr tree);
bool is_close_to_neighbor_voxels(
const pcl::PointXYZ & point, const double distance_threshold, const PointCloudPtr & map,
VoxelGridPointXYZ & voxel) const;
@@ -122,9 +122,8 @@ class VoxelGridMapLoader
const double distance_threshold, const PointCloudPtr & map, VoxelGridPointXYZ & voxel) const;
void publish_downsampled_map(const pcl::PointCloud & downsampled_pc);
- bool is_close_points(
- const pcl::PointXYZ point, const pcl::PointXYZ target_point,
- const double distance_threshold) const;
+ static bool is_close_points(
+ const pcl::PointXYZ point, const pcl::PointXYZ target_point, const double distance_threshold);
std::string * tf_map_input_frame_;
};
diff --git a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/debugger.hpp b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/debugger.hpp
index 5886474d51b34..e097755c6c506 100644
--- a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/debugger.hpp
+++ b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/debugger.hpp
@@ -97,7 +97,7 @@ class Debugger
pcl::PointCloud::Ptr pointcloud_within_polygon_;
private:
- inline pcl::PointCloud::Ptr toXYZ(
+ inline static pcl::PointCloud::Ptr toXYZ(
const pcl::PointCloud::Ptr & pointcloud)
{
pcl::PointCloud::Ptr pointcloud_xyz(new pcl::PointCloud);
diff --git a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp
index 801a693905f93..6d9a11634ea08 100644
--- a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp
+++ b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp
@@ -65,7 +65,7 @@ class Validator
public:
explicit Validator(const PointsNumThresholdParam & points_num_threshold_param);
- inline pcl::PointCloud::Ptr getDebugPointCloudWithinObject()
+ inline pcl::PointCloud::Ptr getDebugPointCloudWithinObject() const
{
return cropped_pointcloud_;
}
@@ -92,7 +92,7 @@ class Validator2D : public Validator
public:
explicit Validator2D(PointsNumThresholdParam & points_num_threshold_param);
- pcl::PointCloud::Ptr convertToXYZ(
+ static pcl::PointCloud::Ptr convertToXYZ(
const pcl::PointCloud::Ptr & pointcloud_xy);
inline pcl::PointCloud::Ptr getDebugNeighborPointCloud() override
{
diff --git a/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp b/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp
index bda42aa5f0b55..39dd3db10cfa9 100644
--- a/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp
+++ b/perception/autoware_detection_by_tracker/src/debugger/debugger.hpp
@@ -104,7 +104,7 @@ class Debugger
std::unique_ptr> stop_watch_ptr_;
std::unique_ptr processing_time_publisher_;
- autoware_perception_msgs::msg::DetectedObjects removeFeature(
+ static autoware_perception_msgs::msg::DetectedObjects removeFeature(
const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input)
{
autoware_perception_msgs::msg::DetectedObjects objects;
diff --git a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp
index dd5ce96a858cd..4d45f5df07027 100644
--- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp
+++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp
@@ -115,6 +115,8 @@ RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptio
std::bind(&RANSACGroundFilterComponent::paramCallback, this, _1));
pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
+
+ static_tf_buffer_ = std::make_unique();
}
void RANSACGroundFilterComponent::setDebugPublisher()
@@ -161,20 +163,8 @@ bool RANSACGroundFilterComponent::transformPointCloud(
return true;
}
- geometry_msgs::msg::TransformStamped transform_stamped;
- try {
- transform_stamped = tf_buffer_->lookupTransform(
- in_target_frame, in_cloud_ptr->header.frame_id, in_cloud_ptr->header.stamp,
- rclcpp::Duration::from_seconds(1.0));
- } catch (tf2::TransformException & ex) {
- RCLCPP_WARN(this->get_logger(), "%s", ex.what());
- return false;
- }
- // tf2::doTransform(*in_cloud_ptr, *out_cloud_ptr, transform_stamped);
- Eigen::Matrix4f mat = tf2::transformToEigen(transform_stamped.transform).matrix().cast();
- pcl_ros::transformPointCloud(mat, *in_cloud_ptr, *out_cloud_ptr);
- out_cloud_ptr->header.frame_id = in_target_frame;
- return true;
+ return static_tf_buffer_->transformPointcloud(
+ this, in_target_frame, *in_cloud_ptr, *out_cloud_ptr);
}
void RANSACGroundFilterComponent::extractPointsIndices(
diff --git a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp
index e173fe131602f..bdc217e80650c 100644
--- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp
+++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.hpp
@@ -17,6 +17,8 @@
#include "autoware/pointcloud_preprocessor/filter.hpp"
+#include
+
#include
#include
@@ -35,6 +37,7 @@
#include
#include
+#include
#include
#include
@@ -80,6 +83,7 @@ class RANSACGroundFilterComponent : public autoware::pointcloud_preprocessor::Fi
bool debug_ = false;
bool is_initialized_debug_message_ = false;
Eigen::Vector3d unit_vec_ = Eigen::Vector3d::UnitZ();
+ std::unique_ptr static_tf_buffer_{nullptr};
/*!
* Output transformed PointCloud from in_cloud_ptr->header.frame_id to in_target_frame
diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp
index 2745606697a20..40c00e082c60e 100644
--- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp
+++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp
@@ -467,12 +467,12 @@ void ScanGroundFilterComponent::classifyPointCloud(
for (size_t i = 0; i < in_radial_ordered_clouds.size(); ++i) {
float prev_gnd_radius = 0.0f;
float prev_gnd_slope = 0.0f;
- float points_distance = 0.0f;
PointsCentroid ground_cluster, non_ground_cluster;
PointLabel prev_point_label = PointLabel::INIT;
pcl::PointXYZ prev_gnd_point(0, 0, 0), p_orig_point, prev_p_orig_point;
// loop through each point in the radial div
for (size_t j = 0; j < in_radial_ordered_clouds[i].size(); ++j) {
+ float points_distance = 0.0f;
const float local_slope_max_angle = local_slope_max_angle_rad_;
prev_p_orig_point = p_orig_point;
auto * p = &in_radial_ordered_clouds[i][j];
diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp
index ad5d0ea4b6bc6..94ef16042ff33 100644
--- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp
+++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp
@@ -91,7 +91,14 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt
std::vector height_list;
PointsCentroid()
- : radius_sum(0.0f), height_sum(0.0f), radius_avg(0.0f), height_avg(0.0f), point_num(0)
+ : radius_sum(0.0f),
+ height_sum(0.0f),
+ radius_avg(0.0f),
+ height_avg(0.0f),
+ height_max(0.0f),
+ height_min(10.0f),
+ point_num(0),
+ grid_id(0)
{
}
@@ -128,18 +135,18 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt
float getAverageSlope() { return std::atan2(height_avg, radius_avg); }
- float getAverageHeight() { return height_avg; }
+ float getAverageHeight() const { return height_avg; }
- float getAverageRadius() { return radius_avg; }
+ float getAverageRadius() const { return radius_avg; }
- float getMaxHeight() { return height_max; }
+ float getMaxHeight() const { return height_max; }
- float getMinHeight() { return height_min; }
+ float getMinHeight() const { return height_min; }
- uint16_t getGridId() { return grid_id; }
+ uint16_t getGridId() const { return grid_id; }
- pcl::PointIndices getIndices() { return pcl_indices; }
- std::vector getHeightList() { return height_list; }
+ pcl::PointIndices getIndices() const { return pcl_indices; }
+ std::vector getHeightList() const { return height_list; }
pcl::PointIndices & getIndicesRef() { return pcl_indices; }
std::vector & getHeightListRef() { return height_list; }
diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/postprocess_kernel.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/postprocess_kernel.hpp
index 4792fed3e9362..6ea9965f4fac0 100644
--- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/postprocess_kernel.hpp
+++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/postprocess_kernel.hpp
@@ -19,7 +19,6 @@
#include "autoware/lidar_centerpoint/utils.hpp"
#include "cuda.h"
#include "cuda_runtime_api.h"
-#include "thrust/device_vector.h"
#include
@@ -37,8 +36,6 @@ class PostProcessCUDA
private:
CenterPointConfig config_;
- thrust::device_vector boxes3d_d_;
- thrust::device_vector yaw_norm_thresholds_d_;
};
} // namespace autoware::lidar_centerpoint
diff --git a/perception/autoware_lidar_centerpoint/lib/postprocess/postprocess_kernel.cu b/perception/autoware_lidar_centerpoint/lib/postprocess/postprocess_kernel.cu
index e1af8f36eb082..81157e07991d1 100644
--- a/perception/autoware_lidar_centerpoint/lib/postprocess/postprocess_kernel.cu
+++ b/perception/autoware_lidar_centerpoint/lib/postprocess/postprocess_kernel.cu
@@ -137,10 +137,6 @@ __global__ void generateBoxes3D_kernel(
PostProcessCUDA::PostProcessCUDA(const CenterPointConfig & config) : config_(config)
{
- const auto num_raw_boxes3d = config.down_grid_size_y_ * config.down_grid_size_x_;
- boxes3d_d_ = thrust::device_vector(num_raw_boxes3d);
- yaw_norm_thresholds_d_ = thrust::device_vector(
- config_.yaw_norm_thresholds_.begin(), config_.yaw_norm_thresholds_.end());
}
// cspell: ignore divup
@@ -153,23 +149,26 @@ cudaError_t PostProcessCUDA::generateDetectedBoxes3D_launch(
divup(config_.down_grid_size_y_, THREADS_PER_BLOCK),
divup(config_.down_grid_size_x_, THREADS_PER_BLOCK));
dim3 threads(THREADS_PER_BLOCK, THREADS_PER_BLOCK);
+ auto boxes3d_d =
+ thrust::device_vector(config_.down_grid_size_y_ * config_.down_grid_size_x_);
+ auto yaw_norm_thresholds_d = thrust::device_vector(
+ config_.yaw_norm_thresholds_.begin(), config_.yaw_norm_thresholds_.end());
generateBoxes3D_kernel<<>>(
out_heatmap, out_offset, out_z, out_dim, out_rot, out_vel, config_.voxel_size_x_,
config_.voxel_size_y_, config_.range_min_x_, config_.range_min_y_, config_.down_grid_size_x_,
config_.down_grid_size_y_, config_.downsample_factor_, config_.class_size_,
- config_.has_variance_, thrust::raw_pointer_cast(yaw_norm_thresholds_d_.data()),
- thrust::raw_pointer_cast(boxes3d_d_.data()));
+ config_.has_variance_, thrust::raw_pointer_cast(yaw_norm_thresholds_d.data()),
+ thrust::raw_pointer_cast(boxes3d_d.data()));
// suppress by score
const auto num_det_boxes3d = thrust::count_if(
- thrust::device, boxes3d_d_.begin(), boxes3d_d_.end(),
- is_score_greater(config_.score_threshold_));
+ thrust::device, boxes3d_d.begin(), boxes3d_d.end(), is_score_greater(config_.score_threshold_));
if (num_det_boxes3d == 0) {
return cudaGetLastError();
}
thrust::device_vector det_boxes3d_d(num_det_boxes3d);
thrust::copy_if(
- thrust::device, boxes3d_d_.begin(), boxes3d_d_.end(), det_boxes3d_d.begin(),
+ thrust::device, boxes3d_d.begin(), boxes3d_d.end(), det_boxes3d_d.begin(),
is_score_greater(config_.score_threshold_));
// sort by score
diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/postprocess/postprocess_kernel.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/postprocess/postprocess_kernel.hpp
index ed677bc84b867..6228fec48a833 100644
--- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/postprocess/postprocess_kernel.hpp
+++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/postprocess/postprocess_kernel.hpp
@@ -20,7 +20,6 @@
#include
#include
-#include
#include
@@ -41,8 +40,6 @@ class PostprocessCuda
cudaStream_t stream_;
cudaStream_t stream_event_;
cudaEvent_t start_, stop_;
- thrust::device_vector boxes3d_d_;
- thrust::device_vector yaw_norm_thresholds_d_;
};
} // namespace autoware::lidar_transfusion
diff --git a/perception/autoware_lidar_transfusion/lib/postprocess/postprocess_kernel.cu b/perception/autoware_lidar_transfusion/lib/postprocess/postprocess_kernel.cu
index fbdb89d59b3d1..905b4ea6f39f4 100644
--- a/perception/autoware_lidar_transfusion/lib/postprocess/postprocess_kernel.cu
+++ b/perception/autoware_lidar_transfusion/lib/postprocess/postprocess_kernel.cu
@@ -93,9 +93,6 @@ __global__ void generateBoxes3D_kernel(
PostprocessCuda::PostprocessCuda(const TransfusionConfig & config, cudaStream_t & stream)
: config_(config), stream_(stream)
{
- boxes3d_d_ = thrust::device_vector(config_.num_proposals_);
- yaw_norm_thresholds_d_ = thrust::device_vector(
- config_.yaw_norm_thresholds_.begin(), config_.yaw_norm_thresholds_.end());
}
// cspell: ignore divup
@@ -106,22 +103,25 @@ cudaError_t PostprocessCuda::generateDetectedBoxes3D_launch(
dim3 threads = {THREADS_PER_BLOCK};
dim3 blocks = {divup(config_.num_proposals_, threads.x)};
+ auto boxes3d_d = thrust::device_vector(config_.num_proposals_);
+ auto yaw_norm_thresholds_d = thrust::device_vector(
+ config_.yaw_norm_thresholds_.begin(), config_.yaw_norm_thresholds_.end());
+
generateBoxes3D_kernel<<>>(
cls_output, box_output, dir_cls_output, config_.voxel_x_size_, config_.voxel_y_size_,
config_.min_x_range_, config_.min_y_range_, config_.num_proposals_, config_.num_classes_,
- config_.num_point_values_, thrust::raw_pointer_cast(yaw_norm_thresholds_d_.data()),
- thrust::raw_pointer_cast(boxes3d_d_.data()));
+ config_.num_point_values_, thrust::raw_pointer_cast(yaw_norm_thresholds_d.data()),
+ thrust::raw_pointer_cast(boxes3d_d.data()));
// suppress by score
const auto num_det_boxes3d = thrust::count_if(
- thrust::device, boxes3d_d_.begin(), boxes3d_d_.end(),
- is_score_greater(config_.score_threshold_));
+ thrust::device, boxes3d_d.begin(), boxes3d_d.end(), is_score_greater(config_.score_threshold_));
if (num_det_boxes3d == 0) {
return cudaGetLastError();
}
thrust::device_vector det_boxes3d_d(num_det_boxes3d);
thrust::copy_if(
- thrust::device, boxes3d_d_.begin(), boxes3d_d_.end(), det_boxes3d_d.begin(),
+ thrust::device, boxes3d_d.begin(), boxes3d_d.end(), det_boxes3d_d.begin(),
is_score_greater(config_.score_threshold_));
// sort by score
diff --git a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp
index 1c677c9d0f6e4..b22609100bee1 100644
--- a/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp
+++ b/perception/autoware_map_based_prediction/include/map_based_prediction/map_based_prediction_node.hpp
@@ -39,6 +39,7 @@
#include
#include
+#include
#include
#include
@@ -178,6 +179,9 @@ class MapBasedPredictionNode : public rclcpp::Node
// Crosswalk Entry Points
lanelet::ConstLanelets crosswalks_;
+ // Fences
+ lanelet::LaneletMapUPtr fence_layer_{nullptr};
+
// Parameters
bool enable_delay_compensation_;
PredictionTimeHorizon prediction_time_horizon_;
diff --git a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp
index b1402724e943d..6b7b3489bf051 100644
--- a/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp
+++ b/perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp
@@ -410,9 +410,9 @@ bool withinRoadLanelet(
}
boost::optional isReachableCrosswalkEdgePoints(
- const TrackedObject & object, const lanelet::ConstLanelet & target_crosswalk,
- const CrosswalkEdgePoints & edge_points, const lanelet::LaneletMapPtr & lanelet_map_ptr,
- const double time_horizon, const double min_object_vel)
+ const TrackedObject & object, const lanelet::ConstLanelets & surrounding_lanelets,
+ const lanelet::ConstLanelets & external_surrounding_crosswalks,
+ const CrosswalkEdgePoints & edge_points, const double time_horizon, const double min_object_vel)
{
using Point = boost::geometry::model::d2::point_xy;
@@ -421,9 +421,6 @@ boost::optional isReachableCrosswalkEdgePoints(
const auto yaw = autoware::universe_utils::getRPY(object.kinematics.pose_with_covariance.pose).z;
lanelet::BasicPoint2d obj_pos_as_lanelet(obj_pos.x, obj_pos.y);
- if (boost::geometry::within(obj_pos_as_lanelet, target_crosswalk.polygon2d().basicPolygon())) {
- return {};
- }
const auto & p1 = edge_points.front_center_point;
const auto & p2 = edge_points.back_center_point;
@@ -441,17 +438,12 @@ boost::optional isReachableCrosswalkEdgePoints(
const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y);
const auto is_stop_object = estimated_velocity < stop_velocity_th;
const auto velocity = std::max(min_object_vel, estimated_velocity);
- const auto surrounding_lanelets = lanelet::geometry::findNearest(
- lanelet_map_ptr->laneletLayer, obj_pos_as_lanelet, time_horizon * velocity);
- const auto isAcrossAnyRoad = [&surrounding_lanelets](const Point & p_src, const Point & p_dst) {
- const auto withinAnyCrosswalk = [&surrounding_lanelets](const Point & p) {
- for (const auto & lanelet : surrounding_lanelets) {
- const lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype);
- if (
- (attr.value() == lanelet::AttributeValueString::Crosswalk ||
- attr.value() == lanelet::AttributeValueString::Walkway) &&
- boost::geometry::within(p, lanelet.second.polygon2d().basicPolygon())) {
+ const auto isAcrossAnyRoad = [&surrounding_lanelets, &external_surrounding_crosswalks](
+ const Point & p_src, const Point & p_dst) {
+ const auto withinAnyCrosswalk = [&external_surrounding_crosswalks](const Point & p) {
+ for (const auto & crosswalk : external_surrounding_crosswalks) {
+ if (boost::geometry::within(p, crosswalk.polygon2d().basicPolygon())) {
return true;
}
}
@@ -470,14 +462,13 @@ boost::optional isReachableCrosswalkEdgePoints(
std::vector points_of_intersect;
const boost::geometry::model::linestring line{p_src, p_dst};
for (const auto & lanelet : surrounding_lanelets) {
- const lanelet::Attribute attr = lanelet.second.attribute(lanelet::AttributeName::Subtype);
+ const lanelet::Attribute attr = lanelet.attribute(lanelet::AttributeName::Subtype);
if (attr.value() != lanelet::AttributeValueString::Road) {
continue;
}
std::vector tmp_intersects;
- boost::geometry::intersection(
- line, lanelet.second.polygon2d().basicPolygon(), tmp_intersects);
+ boost::geometry::intersection(line, lanelet.polygon2d().basicPolygon(), tmp_intersects);
for (const auto & p : tmp_intersects) {
if (isExist(p, points_of_intersect) || withinAnyCrosswalk(p)) {
continue;
@@ -671,7 +662,6 @@ ObjectClassification::_label_type changeLabelForPrediction(
}
case ObjectClassification::PEDESTRIAN: {
- const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
const float max_velocity_for_human_mps =
autoware::universe_utils::kmph2mps(25.0); // Max human being motion speed is 25km/h
const double abs_speed = std::hypot(
@@ -679,7 +669,6 @@ ObjectClassification::_label_type changeLabelForPrediction(
object.kinematics.twist_with_covariance.twist.linear.y);
const bool high_speed_object = abs_speed > max_velocity_for_human_mps;
// fast, human-like object: like segway
- if (within_road_lanelet && high_speed_object) return label; // currently do nothing
// return ObjectClassification::MOTORCYCLE;
if (high_speed_object) return label; // currently do nothing
// fast human outside road lanelet will move like unknown object
@@ -940,6 +929,16 @@ void MapBasedPredictionNode::mapCallback(const LaneletMapBin::ConstSharedPtr msg
const auto walkways = lanelet::utils::query::walkwayLanelets(all_lanelets);
crosswalks_.insert(crosswalks_.end(), crosswalks.begin(), crosswalks.end());
crosswalks_.insert(crosswalks_.end(), walkways.begin(), walkways.end());
+
+ lanelet::LineStrings3d fences;
+ for (const auto & linestring : lanelet_map_ptr_->lineStringLayer) {
+ if (const std::string type = linestring.attributeOr(lanelet::AttributeName::Type, "none");
+ type == "fence") {
+ fences.push_back(lanelet::LineString3d(
+ std::const_pointer_cast(linestring.constData())));
+ }
+ }
+ fence_layer_ = lanelet::utils::createMap(fences);
}
void MapBasedPredictionNode::trafficSignalsCallback(
@@ -1329,10 +1328,9 @@ bool MapBasedPredictionNode::doesPathCrossAnyFence(const PredictedPath & predict
for (const auto & p : predicted_path.path)
predicted_path_ls.emplace_back(p.position.x, p.position.y);
const auto candidates =
- lanelet_map_ptr_->lineStringLayer.search(lanelet::geometry::boundingBox2d(predicted_path_ls));
+ fence_layer_->lineStringLayer.search(lanelet::geometry::boundingBox2d(predicted_path_ls));
for (const auto & candidate : candidates) {
- const std::string type = candidate.attributeOr(lanelet::AttributeName::Type, "none");
- if (type == "fence" && doesPathCrossFence(predicted_path, candidate)) {
+ if (doesPathCrossFence(predicted_path, candidate)) {
return true;
}
}
@@ -1384,10 +1382,29 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
}
boost::optional crossing_crosswalk{boost::none};
- for (const auto & crosswalk : crosswalks_) {
- if (withinLanelet(object, crosswalk)) {
- crossing_crosswalk = crosswalk;
- break;
+ const auto & obj_pos = object.kinematics.pose_with_covariance.pose.position;
+ const auto & obj_vel = object.kinematics.twist_with_covariance.twist.linear;
+ const auto estimated_velocity = std::hypot(obj_vel.x, obj_vel.y);
+ const auto velocity = std::max(min_crosswalk_user_velocity_, estimated_velocity);
+ // TODO(Mamoru Sobue): 3rd argument of findNearest is the number of lanelets, not radius, so past
+ // implementation has been wrong.
+ const auto surrounding_lanelets_with_dist = lanelet::geometry::findNearest(
+ lanelet_map_ptr_->laneletLayer, lanelet::BasicPoint2d{obj_pos.x, obj_pos.y},
+ prediction_time_horizon_.pedestrian * velocity);
+ lanelet::ConstLanelets surrounding_lanelets;
+ lanelet::ConstLanelets external_surrounding_crosswalks;
+ for (const auto & [dist, lanelet] : surrounding_lanelets_with_dist) {
+ surrounding_lanelets.push_back(lanelet);
+ const auto attr = lanelet.attribute(lanelet::AttributeName::Subtype);
+ if (
+ attr.value() == lanelet::AttributeValueString::Crosswalk ||
+ attr.value() == lanelet::AttributeValueString::Walkway) {
+ const auto & crosswalk = lanelet;
+ if (withinLanelet(object, crosswalk)) {
+ crossing_crosswalk = crosswalk;
+ } else {
+ external_surrounding_crosswalks.push_back(crosswalk);
+ }
}
}
@@ -1448,8 +1465,9 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
}
}
- // try to find the edge points for all crosswalks and generate path to the crosswalk edge
- for (const auto & crosswalk : crosswalks_) {
+ // try to find the edge points for other surrounding crosswalks and generate path to the crosswalk
+ // edge
+ for (const auto & crosswalk : external_surrounding_crosswalks) {
const auto crosswalk_signal_id_opt = getTrafficSignalId(crosswalk);
if (crosswalk_signal_id_opt.has_value() && use_crosswalk_signal_) {
if (!calcIntentionToCrossWithTrafficSignal(
@@ -1474,8 +1492,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
}
const auto reachable_crosswalk = isReachableCrosswalkEdgePoints(
- object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_.pedestrian,
- min_crosswalk_user_velocity_);
+ object, surrounding_lanelets, external_surrounding_crosswalks, edge_points,
+ prediction_time_horizon_.pedestrian, min_crosswalk_user_velocity_);
if (!reachable_crosswalk) {
continue;
@@ -2384,9 +2402,15 @@ std::vector MapBasedPredictionNode::convertPathType(
continue;
}
- const double lane_yaw = std::atan2(
- current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x);
- current_p.orientation = autoware::universe_utils::createQuaternionFromYaw(lane_yaw);
+ const double dx = current_p.position.x - prev_p.position.x;
+ const double dy = current_p.position.y - prev_p.position.y;
+ const double sin_yaw_half = dy / (std::sqrt(dx * dx + dy * dy) + dx);
+ const double cos_yaw_half = std::sqrt(1 - sin_yaw_half * sin_yaw_half);
+ current_p.orientation.x = 0.0;
+ current_p.orientation.y = 0.0;
+ current_p.orientation.z = sin_yaw_half;
+ current_p.orientation.w = cos_yaw_half;
+
converted_path.push_back(current_p);
prev_p = current_p;
}
@@ -2415,17 +2439,29 @@ std::vector MapBasedPredictionNode::convertPathType(
}
}
- const double lane_yaw = std::atan2(
- current_p.position.y - prev_p.position.y, current_p.position.x - prev_p.position.x);
- current_p.orientation = autoware::universe_utils::createQuaternionFromYaw(lane_yaw);
+ const double dx = current_p.position.x - prev_p.position.x;
+ const double dy = current_p.position.y - prev_p.position.y;
+ const double sin_yaw_half = dy / (std::sqrt(dx * dx + dy * dy) + dx);
+ const double cos_yaw_half = std::sqrt(1 - sin_yaw_half * sin_yaw_half);
+ current_p.orientation.x = 0.0;
+ current_p.orientation.y = 0.0;
+ current_p.orientation.z = sin_yaw_half;
+ current_p.orientation.w = cos_yaw_half;
+
converted_path.push_back(current_p);
prev_p = current_p;
}
}
// Resample Path
- const auto resampled_converted_path =
- autoware::motion_utils::resamplePoseVector(converted_path, reference_path_resolution_);
+ const bool use_akima_spline_for_xy = true;
+ const bool use_lerp_for_z = true;
+ // the options use_akima_slpine_for_xy and use_lerp_for_z are set to true
+ // but the implementation of use_akima_slpine_for_xy in resamplePoseVector and
+ // resamplePointVector is opposite to the options so the options are set to true to use linear
+ // interpolation for xy
+ const auto resampled_converted_path = autoware::motion_utils::resamplePoseVector(
+ converted_path, reference_path_resolution_, use_akima_spline_for_xy, use_lerp_for_z);
converted_paths.push_back(resampled_converted_path);
}
diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp
index dac034a6b7a7d..6f2fb8a86b502 100644
--- a/perception/autoware_map_based_prediction/src/path_generator.cpp
+++ b/perception/autoware_map_based_prediction/src/path_generator.cpp
@@ -188,7 +188,7 @@ PredictedPath PathGenerator::generatePolynomialPath(
{
// Get current Frenet Point
const double ref_path_len = autoware::motion_utils::calcArcLength(ref_path);
- const auto current_point = getFrenetPoint(object, ref_path, speed_limit, duration);
+ const auto current_point = getFrenetPoint(object, ref_path, duration, speed_limit);
// Step1. Set Target Frenet Point
// Note that we do not set position s,
diff --git a/perception/autoware_multi_object_tracker/schema/data_association_matrix.schema.json b/perception/autoware_multi_object_tracker/schema/data_association_matrix.schema.json
index daf9d9f957b7c..3235ba5f5ea2a 100644
--- a/perception/autoware_multi_object_tracker/schema/data_association_matrix.schema.json
+++ b/perception/autoware_multi_object_tracker/schema/data_association_matrix.schema.json
@@ -11,42 +11,80 @@
"description": "Assignment table for data association.",
"items": {
"type": "integer"
- }
+ },
+ "default": [
+ 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1,
+ 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0,
+ 0, 0, 0, 1, 1, 1
+ ]
},
"max_dist_matrix": {
"type": "array",
"description": "Maximum distance table for data association.",
"items": {
"type": "number"
- }
+ },
+ "default": [
+ 4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 4.0,
+ 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 4.0, 2.0,
+ 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 3.0, 1.0, 1.0,
+ 1.0, 1.0, 3.0, 3.0, 2.0, 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0
+ ]
},
"max_area_matrix": {
"type": "array",
"description": "Maximum area table for data association.",
"items": {
"type": "number"
- }
+ },
+ "default": [
+ 100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 12.1, 12.1, 36.0, 60.0, 60.0,
+ 10000.0, 10000.0, 10000.0, 36.0, 12.1, 36.0, 60.0, 60.0, 10000.0, 10000.0, 10000.0,
+ 60.0, 12.1, 36.0, 60.0, 60.0, 10000.0, 10000.0, 10000.0, 60.0, 12.1, 36.0, 60.0, 60.0,
+ 10000.0, 10000.0, 10000.0, 2.5, 10000.0, 10000.0, 10000.0, 10000.0, 2.5, 2.5, 1.0, 2.5,
+ 10000.0, 10000.0, 10000.0, 10000.0, 2.5, 2.5, 1.0, 2.0, 10000.0, 10000.0, 10000.0,
+ 10000.0, 1.5, 1.5, 1.0
+ ]
},
"min_area_matrix": {
"type": "array",
"description": "Minimum area table for data association.",
"items": {
"type": "number"
- }
+ },
+ "default": [
+ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.6, 3.6, 6.0, 10.0, 10.0, 0.0, 0.0, 0.0, 6.0,
+ 3.6, 6.0, 10.0, 10.0, 0.0, 0.0, 0.0, 10.0, 3.6, 6.0, 10.0, 10.0, 0.0, 0.0, 0.0, 10.0,
+ 3.6, 6.0, 10.0, 10.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1, 0.001,
+ 0.0, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1, 0.001, 0.0, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1
+ ]
},
"max_rad_matrix": {
"type": "array",
"description": "Maximum angle table for data association.",
"items": {
"type": "number"
- }
+ },
+ "default": [
+ 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15,
+ 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047,
+ 1.047, 1.047, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, 3.15, 3.15,
+ 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15,
+ 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15
+ ]
},
"min_iou_matrix": {
"type": "array",
"description": "A matrix that represents the minimum Intersection over Union (IoU) limit allowed for assignment.",
"items": {
"type": "number"
- }
+ },
+ "default": [
+ 0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, 0.1,
+ 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.2,
+ 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1,
+ 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001
+ ]
}
},
"required": [
diff --git a/perception/autoware_multi_object_tracker/schema/input_channels.schema.json b/perception/autoware_multi_object_tracker/schema/input_channels.schema.json
index 3c3da4d3f70a0..96f612828b597 100644
--- a/perception/autoware_multi_object_tracker/schema/input_channels.schema.json
+++ b/perception/autoware_multi_object_tracker/schema/input_channels.schema.json
@@ -41,18 +41,138 @@
"input_channels": {
"type": "object",
"properties": {
- "detected_objects": { "$ref": "#/definitions/input_channel" },
- "lidar_clustering": { "$ref": "#/definitions/input_channel" },
- "lidar_centerpoint": { "$ref": "#/definitions/input_channel" },
- "lidar_centerpoint_validated": { "$ref": "#/definitions/input_channel" },
- "lidar_apollo": { "$ref": "#/definitions/input_channel" },
- "lidar_apollo_validated": { "$ref": "#/definitions/input_channel" },
- "lidar_pointpainitng": { "$ref": "#/definitions/input_channel" },
- "lidar_pointpainting_validated": { "$ref": "#/definitions/input_channel" },
- "camera_lidar_fusion": { "$ref": "#/definitions/input_channel" },
- "detection_by_tracker": { "$ref": "#/definitions/input_channel" },
- "radar": { "$ref": "#/definitions/input_channel" },
- "radar_far": { "$ref": "#/definitions/input_channel" }
+ "detected_objects": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "detected_objects",
+ "short_name": "all"
+ }
+ }
+ },
+ "lidar_clustering": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/clustering/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "clustering",
+ "short_name": "Lcl"
+ }
+ }
+ },
+ "lidar_centerpoint": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/centerpoint/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "centerpoint",
+ "short_name": "Lcp"
+ }
+ }
+ },
+ "lidar_centerpoint_validated": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/centerpoint/validation/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "centerpoint",
+ "short_name": "Lcp"
+ }
+ }
+ },
+ "lidar_apollo": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/apollo/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "apollo",
+ "short_name": "Lap"
+ }
+ }
+ },
+ "lidar_apollo_validated": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/apollo/validation/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "apollo",
+ "short_name": "Lap"
+ }
+ }
+ },
+ "lidar_pointpainitng": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/pointpainting/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "pointpainting",
+ "short_name": "Lpp"
+ }
+ }
+ },
+ "lidar_pointpainting_validated": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/pointpainting/validation/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "pointpainting",
+ "short_name": "Lpp"
+ }
+ }
+ },
+ "camera_lidar_fusion": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/clustering/camera_lidar_fusion/objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "camera_lidar_fusion",
+ "short_name": "CLf"
+ }
+ }
+ },
+ "detection_by_tracker": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/detection_by_tracker/objects",
+ "can_spawn_new_tracker": false,
+ "optional": {
+ "name": "detection_by_tracker",
+ "short_name": "dbT"
+ }
+ }
+ },
+ "radar": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/sensing/radar/detected_objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "radar",
+ "short_name": "R"
+ }
+ }
+ },
+ "radar_far": {
+ "$ref": "#/definitions/input_channel",
+ "default": {
+ "topic": "/perception/object_recognition/detection/radar/far_objects",
+ "can_spawn_new_tracker": true,
+ "optional": {
+ "name": "radar_far",
+ "short_name": "Rf"
+ }
+ }
+ }
},
"required": [
"detected_objects",
diff --git a/perception/autoware_multi_object_tracker/src/debugger/debugger.hpp b/perception/autoware_multi_object_tracker/src/debugger/debugger.hpp
index 77618e1882be7..79dfb3720b626 100644
--- a/perception/autoware_multi_object_tracker/src/debugger/debugger.hpp
+++ b/perception/autoware_multi_object_tracker/src/debugger/debugger.hpp
@@ -91,7 +91,8 @@ class TrackerDebugger
void endMeasurementTime(const rclcpp::Time & now);
void startPublishTime(const rclcpp::Time & now);
void endPublishTime(const rclcpp::Time & now, const rclcpp::Time & object_time);
- void checkDelay(diagnostic_updater::DiagnosticStatusWrapper & stat);
+ void checkDelay(
+ diagnostic_updater::DiagnosticStatusWrapper & stat); // cppcheck-suppress functionConst
// Debug object
void setObjectChannels(const std::vector & channels)
diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp
index 45955ac983dde..89d8cbaeb3bd8 100644
--- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp
+++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.cpp
@@ -153,9 +153,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options)
// If the delay compensation is enabled, the timer is used to publish the output at the correct
// time.
if (enable_delay_compensation) {
- publisher_period_ = 1.0 / publish_rate; // [s]
- constexpr double timer_multiplier = 20.0; // 20 times frequent for publish timing check
- const auto timer_period = rclcpp::Rate(publish_rate * timer_multiplier).period();
+ const auto timer_period = rclcpp::Rate(publish_rate).period();
publish_timer_ = rclcpp::create_timer(
this, get_clock(), timer_period, std::bind(&MultiObjectTracker::onTimer, this));
}
@@ -210,35 +208,13 @@ void MultiObjectTracker::onTrigger()
ObjectsList objects_list;
const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list);
if (!is_objects_ready) return;
-
onMessage(objects_list);
- const rclcpp::Time latest_time(objects_list.back().second.header.stamp);
-
- // Publish objects if the timer is not enabled
- if (publish_timer_ == nullptr) {
- // if the delay compensation is disabled, publish the objects in the latest time
- publish(latest_time);
- } else {
- // Publish if the next publish time is close
- const double minimum_publish_interval = publisher_period_ * 0.70; // 70% of the period
- const rclcpp::Time publish_time = this->now();
- if ((publish_time - last_published_time_).seconds() > minimum_publish_interval) {
- checkAndPublish(publish_time);
- }
- }
}
void MultiObjectTracker::onTimer()
{
const rclcpp::Time current_time = this->now();
- // Check the publish period
- const auto elapsed_time = (current_time - last_published_time_).seconds();
- // If the elapsed time is over the period, publish objects with prediction
- constexpr double maximum_latency_ratio = 1.11; // 11% margin
- const double maximum_publish_latency = publisher_period_ * maximum_latency_ratio;
- if (elapsed_time < maximum_publish_latency) return;
-
// get objects from the input manager and run process
ObjectsList objects_list;
const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list);
diff --git a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp
index db5eaaa88ca8c..e917acbda9fcc 100644
--- a/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp
+++ b/perception/autoware_multi_object_tracker/src/multi_object_tracker_node.hpp
@@ -78,7 +78,6 @@ class MultiObjectTracker : public rclcpp::Node
// publish timer
rclcpp::TimerBase::SharedPtr publish_timer_;
rclcpp::Time last_published_time_;
- double publisher_period_;
// internal states
std::string world_frame_id_; // tracking frame
diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp
index 432a4105d815f..ee2c6910159b5 100644
--- a/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp
+++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp
@@ -60,7 +60,7 @@ class InputStream
void getObjectsOlderThan(
const rclcpp::Time & object_latest_time, const rclcpp::Time & object_oldest_time,
ObjectsList & objects_list);
- void getNames(std::string & long_name, std::string & short_name)
+ void getNames(std::string & long_name, std::string & short_name) const
{
long_name = long_name_;
short_name = short_name_;
@@ -94,7 +94,7 @@ class InputStream
std::string input_topic_;
std::string long_name_;
std::string short_name_;
- bool is_spawn_enabled_;
+ bool is_spawn_enabled_{};
size_t que_size_{30};
std::deque objects_que_;
@@ -103,11 +103,11 @@ class InputStream
// bool is_time_initialized_{false};
int initial_count_{0};
- double expected_interval_;
- double latency_mean_;
- double latency_var_;
- double interval_mean_;
- double interval_var_;
+ double expected_interval_{};
+ double latency_mean_{};
+ double latency_var_{};
+ double interval_mean_{};
+ double interval_var_{};
rclcpp::Time latest_measurement_time_;
rclcpp::Time latest_message_time_;
@@ -136,7 +136,7 @@ class InputManager
bool is_initialized_{false};
rclcpp::Time latest_exported_object_time_;
- size_t input_size_;
+ size_t input_size_{};
std::vector> input_streams_;
std::function func_trigger_;
diff --git a/perception/autoware_object_merger/README.md b/perception/autoware_object_merger/README.md
index f9d8c91b2a4c1..c65353efa3a91 100644
--- a/perception/autoware_object_merger/README.md
+++ b/perception/autoware_object_merger/README.md
@@ -25,9 +25,9 @@ The successive shortest path algorithm is used to solve the data association pro
## Parameters
-{{ json_to_markdown("perception/object_merger/schema/object_association_merger.schema.json") }}
-{{ json_to_markdown("perception/object_merger/schema/data_association_matrix.schema.json") }}
-{{ json_to_markdown("perception/object_merger/schema/overlapped_judge.schema.json") }}
+{{ json_to_markdown("perception/autoware_object_merger/schema/object_association_merger.schema.json") }}
+{{ json_to_markdown("perception/autoware_object_merger/schema/data_association_matrix.schema.json") }}
+{{ json_to_markdown("perception/autoware_object_merger/schema/overlapped_judge.schema.json") }}
## Tips
diff --git a/perception/autoware_object_range_splitter/README.md b/perception/autoware_object_range_splitter/README.md
index 3cdfe36528094..dbb6c2a48faab 100644
--- a/perception/autoware_object_range_splitter/README.md
+++ b/perception/autoware_object_range_splitter/README.md
@@ -43,7 +43,7 @@ Example:
## Parameters
-{{ json_to_markdown("perception/object_range_splitter/schema/object_range_splitter.schema.json") }}
+{{ json_to_markdown("perception/autoware_object_range_splitter/schema/object_range_splitter.schema.json") }}
## Assumptions / Known limits
diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp
index b940b932db0ef..518052a1a4b8c 100644
--- a/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp
+++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/costmap_2d/occupancy_grid_map_fixed.cpp
@@ -81,9 +81,9 @@ void OccupancyGridMapFixedBlindSpot::updateWithPointCloud(
: range(_range), wx(_wx), wy(_wy)
{
}
- double range;
- double wx;
- double wy;
+ double range{};
+ double wx{};
+ double wy{};
};
std::vector*angle bin*/ std::vector> obstacle_pointcloud_angle_bins(angle_bin_size);
diff --git a/perception/autoware_probabilistic_occupancy_grid_map/lib/fusion_policy/fusion_policy.cpp b/perception/autoware_probabilistic_occupancy_grid_map/lib/fusion_policy/fusion_policy.cpp
index 6d058b3bef6eb..993e220786de8 100644
--- a/perception/autoware_probabilistic_occupancy_grid_map/lib/fusion_policy/fusion_policy.cpp
+++ b/perception/autoware_probabilistic_occupancy_grid_map/lib/fusion_policy/fusion_policy.cpp
@@ -202,17 +202,17 @@ struct dempsterShaferOccupancy
}
// calc conflict factor K
- double calcK(const dempsterShaferOccupancy & other)
+ double calcK(const dempsterShaferOccupancy & other) const
{
return (occupied * other.empty + empty * other.occupied);
}
// calc sum of occupied probability mass
- double calcOccupied(const dempsterShaferOccupancy & other)
+ double calcOccupied(const dempsterShaferOccupancy & other) const
{
return occupied * other.occupied + occupied * other.unknown + unknown * other.occupied;
}
// calc sum of empty probability mass
- double calcEmpty(const dempsterShaferOccupancy & other)
+ double calcEmpty(const dempsterShaferOccupancy & other) const
{
return empty * other.empty + empty * other.unknown + unknown * other.empty;
}
@@ -240,7 +240,7 @@ struct dempsterShaferOccupancy
}
// get occupancy probability via Pignistic Probability
- double getPignisticProbability() { return occupied + unknown / 2.0; }
+ double getPignisticProbability() const { return occupied + unknown / 2.0; }
};
/**
diff --git a/perception/autoware_radar_fusion_to_detected_object/src/include/radar_fusion_to_detected_object.hpp b/perception/autoware_radar_fusion_to_detected_object/src/include/radar_fusion_to_detected_object.hpp
index b296f52e2c139..3c95d8f068af1 100644
--- a/perception/autoware_radar_fusion_to_detected_object/src/include/radar_fusion_to_detected_object.hpp
+++ b/perception/autoware_radar_fusion_to_detected_object/src/include/radar_fusion_to_detected_object.hpp
@@ -99,9 +99,9 @@ class RadarFusionToDetectedObject
// std::vector splitObject(
// const DetectedObject & object, const std::shared_ptr> & radars);
TwistWithCovariance estimateTwist(
- const DetectedObject & object, const std::shared_ptr> & radars);
+ const DetectedObject & object, const std::shared_ptr> & radars) const;
bool isQualified(
- const DetectedObject & object, const std::shared_ptr> & radars);
+ const DetectedObject & object, const std::shared_ptr> & radars) const;
TwistWithCovariance convertDopplerToTwist(
const DetectedObject & object, const TwistWithCovariance & twist_with_covariance);
static bool isYawCorrect(
diff --git a/perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp b/perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp
index bc96ac780fd0a..25e174a44c2ec 100644
--- a/perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp
+++ b/perception/autoware_radar_fusion_to_detected_object/src/radar_fusion_to_detected_object.cpp
@@ -205,7 +205,7 @@ RadarFusionToDetectedObject::filterRadarWithinObject(
// (Target value is amplitude if using radar pointcloud. Target value is probability if using radar
// objects).
TwistWithCovariance RadarFusionToDetectedObject::estimateTwist(
- const DetectedObject & object, const std::shared_ptr> & radars)
+ const DetectedObject & object, const std::shared_ptr> & radars) const
{
if (!radars || (*radars).empty()) {
TwistWithCovariance output{};
@@ -298,7 +298,7 @@ TwistWithCovariance RadarFusionToDetectedObject::estimateTwist(
// Judge whether low confidence objects that do not have some radar points/objects or not.
bool RadarFusionToDetectedObject::isQualified(
- const DetectedObject & object, const std::shared_ptr> & radars)
+ const DetectedObject & object, const std::shared_ptr> & radars) const
{
if (object.existence_probability > param_.threshold_probability) {
return true;
diff --git a/perception/autoware_radar_tracks_msgs_converter/README.md b/perception/autoware_radar_tracks_msgs_converter/README.md
index 2883ddaecf926..5010f5f873932 100644
--- a/perception/autoware_radar_tracks_msgs_converter/README.md
+++ b/perception/autoware_radar_tracks_msgs_converter/README.md
@@ -1,6 +1,6 @@
# radar_tracks_msgs_converter
-This package converts from [radar_msgs/msg/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) into [autoware_perception_msgs/msg/DetectedObject] and [autoware_perception_msgs/msg/TrackedObject](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_perception_msgs/msg/TrackedObject.msg).
+This package converts from [radar_msgs/msg/RadarTracks](https://github.com/ros-perception/radar_msgs/blob/ros2/msg/RadarTracks.msg) into [autoware_perception_msgs/msg/DetectedObject](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_perception_msgs/msg/DetectedObject.msg) and [autoware_perception_msgs/msg/TrackedObject](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_perception_msgs/msg/TrackedObject.msg).
- Calculation cost is O(n).
- n: The number of radar objects
@@ -54,7 +54,7 @@ Autoware objects label is defined in [ObjectClassification](https://github.com/a
#### Parameter Summary
-{{ json_to_markdown("perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json") }}
+{{ json_to_markdown("perception/autoware_radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json") }}
#### Parameter Description
diff --git a/perception/autoware_shape_estimation/CMakeLists.txt b/perception/autoware_shape_estimation/CMakeLists.txt
index b19f422c28d27..96bf946ab11db 100644
--- a/perception/autoware_shape_estimation/CMakeLists.txt
+++ b/perception/autoware_shape_estimation/CMakeLists.txt
@@ -10,13 +10,17 @@ find_package(pcl_conversions REQUIRED)
find_package(OpenCV REQUIRED)
find_package(Eigen3 REQUIRED)
+find_package(CUDA)
+find_package(CUDNN)
+find_package(TENSORRT)
+
set(SHAPE_ESTIMATION_DEPENDENCIES
PCL
OpenCV
Eigen3
)
-ament_auto_add_library(${PROJECT_NAME}_lib SHARED
+set(${PROJECT_NAME}_SOURCES
lib/shape_estimator.cpp
lib/model/bounding_box.cpp
lib/model/convex_hull.cpp
@@ -31,6 +35,19 @@ ament_auto_add_library(${PROJECT_NAME}_lib SHARED
lib/corrector/no_corrector.cpp
)
+if(${CUDA_FOUND} AND ${CUDNN_FOUND} AND ${TENSORRT_FOUND})
+ message("CUDA found, including CUDA-specific sources")
+ list(APPEND ${PROJECT_NAME}_SOURCES lib/tensorrt_shape_estimator.cpp)
+ add_definitions(-DUSE_CUDA)
+else()
+ message("CUDA not found, excluding CUDA-specific sources")
+endif()
+
+ament_auto_add_library(${PROJECT_NAME}_lib
+ SHARED
+ ${${PROJECT_NAME}_SOURCES}
+)
+
ament_target_dependencies(${PROJECT_NAME}_lib ${SHAPE_ESTIMATION_DEPENDENCIES})
target_include_directories(${PROJECT_NAME}_lib
@@ -39,6 +56,13 @@ target_include_directories(${PROJECT_NAME}_lib
"${EIGEN3_INCLUDE_DIR}"
)
+if(${CUDA_FOUND} AND ${CUDNN_FOUND} AND ${TENSORRT_FOUND})
+target_include_directories(${PROJECT_NAME}_lib
+ SYSTEM PUBLIC
+ "${TENSORRT_INCLUDE_DIRS}"
+)
+endif()
+
ament_auto_add_library(${PROJECT_NAME} SHARED
src/shape_estimation_node.cpp
)
@@ -57,6 +81,16 @@ target_link_libraries(${PROJECT_NAME}
${PROJECT_NAME}_lib
)
+if(${CUDA_FOUND} AND ${CUDNN_FOUND} AND ${TENSORRT_FOUND})
+ target_link_libraries(${PROJECT_NAME}
+ ${TENSORRT_LIBRARIES}
+ )
+endif()
+
+target_compile_definitions(${PROJECT_NAME} PRIVATE
+ TENSORRT_VERSION_MAJOR=${TENSORRT_VERSION_MAJOR}
+)
+
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::shape_estimation::ShapeEstimationNode"
EXECUTABLE shape_estimation_node
@@ -79,6 +113,6 @@ if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_shape_estimation ${test_files})
target_link_libraries(test_shape_estimation
- ${PROJECT_NAME}
+ ${PROJECT_NAME}
)
endif()
diff --git a/perception/autoware_shape_estimation/README.md b/perception/autoware_shape_estimation/README.md
index 5f184c32f1805..d3cb88ae130d1 100644
--- a/perception/autoware_shape_estimation/README.md
+++ b/perception/autoware_shape_estimation/README.md
@@ -10,7 +10,8 @@ This node calculates a refined object shape (bounding box, cylinder, convex hull
- bounding box
- L-shape fitting. See reference below for details.
+ - L-shape fitting: See reference below for details
+ - ML based shape fitting: See ML Based Shape Fitting Implementation section below for details
- cylinder
@@ -38,6 +39,118 @@ This node calculates a refined object shape (bounding box, cylinder, convex hull
{{ json_to_markdown("perception/autoware_shape_estimation/schema/shape_estimation.schema.json") }}
+## ML Based Shape Implementation
+
+The model takes a point cloud and object label(provided by camera detections/Apollo instance segmentation) as an input and outputs the 3D bounding box of the object.
+
+ML based shape estimation algorithm uses a PointNet model as a backbone to estimate the 3D bounding box of the object. The model is trained on the NuScenes dataset with vehicle labels (Car, Truck, Bus, Trailer).
+
+The implemented model is concatenated with STN (Spatial Transformer Network) to learn the transformation of the input point cloud to the canonical space and PointNet to predict the 3D bounding box of the object.
+Bounding box estimation part of _Frustum PointNets for 3D Object Detection from RGB-D Data_ paper used as a reference.
+
+The model predicts the following outputs for each object:
+
+- x,y,z coordinates of the object center
+- object heading angle classification result(Uses 12 bins for angle classification - 30 degrees each)
+- object heading angle residuals
+- object size classification result
+- object size residuals
+
+### Training ML Based Shape Estimation Model
+
+To train the model, you need ground truth 3D bounding box annotations. When using the mmdetection3d repository for training a 3D object detection algorithm, these ground truth annotations are
+saved and utilized for data augmentation. These annotations are used as an essential dataset for training the shape estimation model effectively.
+
+### Preparing the Dataset
+
+#### Install MMDetection3D prerequisites
+
+**Step 1.** Download and install Miniconda from the [official website](https://mmpretrain.readthedocs.io/en/latest/get_started.html).
+
+**Step 2.** Create a conda virtual environment and activate it
+
+```bash
+conda create --name train-shape-estimation python=3.8 -y
+conda activate train-shape-estimation
+```
+
+**Step 3.** Install PyTorch
+
+```bash
+conda install pytorch torchvision -c pytorch
+```
+
+#### Install mmdetection3d
+
+**Step 1.** Install MMEngine, MMCV, and MMDetection using MIM
+
+```bash
+pip install -U openmim
+mim install mmengine
+mim install 'mmcv>=2.0.0rc4'
+mim install 'mmdet>=3.0.0rc5, <3.3.0'
+```
+
+**Step 2.** Install Autoware's MMDetection3D fork
+
+```bash
+git clone https://github.com/autowarefoundation/mmdetection3d.git
+cd mmdetection3d
+pip install -v -e .
+```
+
+#### Preparing NuScenes dataset for training
+
+**Step 1.** Download the NuScenes dataset from the [official website](https://www.nuscenes.org/download) and extract the dataset to a folder of your choice.
+
+**Note:** The NuScenes dataset is large and requires significant disk space. Ensure you have enough storage available before proceeding.
+
+**Step 2.** Create a symbolic link to the dataset folder
+
+```bash
+ln -s /path/to/nuscenes/dataset/ /path/to/mmdetection3d/data/nuscenes/
+```
+
+**Step 3.** Prepare the NuScenes data by running:
+
+```bash
+cd mmdetection3d
+python tools/create_data.py nuscenes --root-path ./data/nuscenes --out-dir ./data/nuscenes --extra-tag nuscenes --only-gt-database True
+```
+
+#### Clone Bounding Box Estimator model
+
+```bash
+git clone https://github.com/autowarefoundation/bbox_estimator.git
+```
+
+#### Split the dataset into training and validation sets
+
+```bash
+
+cd bbox_estimator
+python3 utils/split_dbinfos.py --dataset_path /path/to/mmdetection3d/data/nuscenes --classes 'car' 'truck' 'bus' 'trailer' --train_ratio 0.8
+```
+
+### Training and Deploying the model
+
+#### Training the model
+
+```bash
+# Detailed training options can be found in the training script
+# For more details, run `python3 train.py --help`
+python3 train.py --dataset_path /path/to/mmdetection3d/data/nuscenes
+```
+
+#### Deploying the model
+
+```bash
+# Convert the trained model to ONNX format
+python3 onnx_converter.py --weight_path /path/to/best_checkpoint.pth --output_path /path/to/output.onnx
+```
+
+Give the output path of the ONNX model to the `model_path` parameter in the `shape_estimation` node launch file.
+
## Assumptions / Known limits
TBD
@@ -56,3 +169,15 @@ month = {June},
keywords = {autonomous driving, laser scanner, perception, segmentation},
}
```
+
+Frustum PointNets for 3D Object Detection from RGB-D Data:
+
+````bibtex
+@inproceedings{qi2018frustum,
+title={Frustum pointnets for 3d object detection from rgb-d data},
+author={Qi, Charles R and Liu, Wei and Wu, Chenxia and Su, Hao and Guibas, Leonidas J},
+booktitle={Proceedings of the IEEE conference on computer vision and pattern recognition},
+pages={918--927},
+year={2018}
+}```
+````
diff --git a/perception/autoware_shape_estimation/config/shape_estimation.param.yaml b/perception/autoware_shape_estimation/config/shape_estimation.param.yaml
index e277d99d70edd..00af06a3703f2 100644
--- a/perception/autoware_shape_estimation/config/shape_estimation.param.yaml
+++ b/perception/autoware_shape_estimation/config/shape_estimation.param.yaml
@@ -1,8 +1,14 @@
/**:
- ros__parameters:
- use_corrector: true
- use_filter: true
- use_vehicle_reference_yaw: false
- use_vehicle_reference_shape_size: false
- use_boost_bbox_optimizer: false
- fix_filtered_objects_label_to_unknown: true
+ ros__parameters:
+ use_corrector: true
+ use_filter: true
+ use_vehicle_reference_yaw: false
+ use_vehicle_reference_shape_size: false
+ use_boost_bbox_optimizer: false
+ fix_filtered_objects_label_to_unknown: true
+ model_params:
+ use_ml_shape_estimator: false
+ minimum_points: 16
+ precision: "fp32"
+ batch_size: 32
+ build_only: false
diff --git a/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp b/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp
new file mode 100644
index 0000000000000..5d0b7032445c8
--- /dev/null
+++ b/perception/autoware_shape_estimation/include/autoware/shape_estimation/tensorrt_shape_estimator.hpp
@@ -0,0 +1,93 @@
+// Copyright 2018 Autoware Foundation. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef AUTOWARE__SHAPE_ESTIMATION__TENSORRT_SHAPE_ESTIMATOR_HPP_
+#define AUTOWARE__SHAPE_ESTIMATION__TENSORRT_SHAPE_ESTIMATOR_HPP_
+
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+namespace autoware::shape_estimation
+{
+using cuda_utils::CudaUniquePtr;
+using cuda_utils::CudaUniquePtrHost;
+using cuda_utils::makeCudaStream;
+using cuda_utils::StreamUniquePtr;
+
+using autoware_perception_msgs::msg::DetectedObject;
+using autoware_perception_msgs::msg::DetectedObjects;
+using tier4_perception_msgs::msg::DetectedObjectsWithFeature;
+using Label = autoware_perception_msgs::msg::ObjectClassification;
+
+class TrtShapeEstimator
+{
+public:
+ TrtShapeEstimator(
+ const std::string & model_path, const std::string & precision,
+ const tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size = (1 << 30),
+ const tensorrt_common::BuildConfig build_config =
+ tensorrt_common::BuildConfig("MinMax", -1, false, false, false, 0.0));
+
+ ~TrtShapeEstimator();
+
+ bool inference(const DetectedObjectsWithFeature & input, DetectedObjectsWithFeature & output);
+
+private:
+ void preprocess(const DetectedObjectsWithFeature & input);
+
+ bool feed_forward_and_decode(
+ const DetectedObjectsWithFeature & input, DetectedObjectsWithFeature & output);
+
+ void postprocess();
+
+ static double class2angle(int pred_cls, double residual, int num_class);
+
+ StreamUniquePtr stream_{makeCudaStream()};
+ std::unique_ptr trt_common_;
+
+ std::vector input_pc_h_;
+ CudaUniquePtr input_pc_d_;
+
+ std::vector input_one_hot_h_;
+ CudaUniquePtr input_one_hot_d_;
+
+ size_t out_s1center_elem_num_;
+ size_t out_s1center_elem_num_per_batch_;
+ CudaUniquePtr out_s1center_prob_d_;
+ CudaUniquePtrHost out_s1center_prob_h_;
+
+ size_t out_pred_elem_num_;
+ size_t out_pred_elem_num_per_batch_;
+ CudaUniquePtr out_pred_prob_d_;
+ CudaUniquePtrHost out_pred_prob_h_;
+
+ std::vector> g_type_mean_size_;
+ size_t batch_size_;
+};
+} // namespace autoware::shape_estimation
+#endif // AUTOWARE__SHAPE_ESTIMATION__TENSORRT_SHAPE_ESTIMATOR_HPP_
diff --git a/perception/autoware_shape_estimation/launch/shape_estimation.launch.xml b/perception/autoware_shape_estimation/launch/shape_estimation.launch.xml
index 816653013c6c8..40fc0a930ac23 100644
--- a/perception/autoware_shape_estimation/launch/shape_estimation.launch.xml
+++ b/perception/autoware_shape_estimation/launch/shape_estimation.launch.xml
@@ -2,12 +2,16 @@
+
+
+
-
+
+
diff --git a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp
new file mode 100644
index 0000000000000..a097060081dc9
--- /dev/null
+++ b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp
@@ -0,0 +1,338 @@
+// Copyright 2018 Autoware Foundation. All rights reserved.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "autoware/shape_estimation/tensorrt_shape_estimator.hpp"
+
+#include
+
+#include
+
+#include
+#include
+
+namespace autoware::shape_estimation
+{
+TrtShapeEstimator::TrtShapeEstimator(
+ const std::string & model_path, const std::string & precision,
+ const tensorrt_common::BatchConfig & batch_config, const size_t max_workspace_size,
+ const tensorrt_common::BuildConfig build_config)
+{
+ trt_common_ = std::make_unique(
+ model_path, precision, nullptr, batch_config, max_workspace_size, build_config);
+
+ trt_common_->setup();
+
+ if (!trt_common_->isInitialized()) {
+ std::cerr << "Failed to initialize TensorRT" << std::endl;
+ return;
+ }
+
+ const auto pc_input_dims = trt_common_->getBindingDimensions(0);
+ const auto pc_input_size = std::accumulate(
+ pc_input_dims.d + 1, pc_input_dims.d + pc_input_dims.nbDims, 1, std::multiplies());
+ input_pc_d_ = cuda_utils::make_unique(pc_input_size * batch_config[2]);
+ batch_size_ = batch_config[2];
+ const auto one_hot_input_dims = trt_common_->getBindingDimensions(1);
+ const auto one_hot_input_size = std::accumulate(
+ one_hot_input_dims.d + 1, one_hot_input_dims.d + one_hot_input_dims.nbDims, 1,
+ std::multiplies());
+ input_one_hot_d_ = cuda_utils::make_unique(one_hot_input_size * batch_config[2]);
+
+ const auto stage1_center_out_dims = trt_common_->getBindingDimensions(2);
+ out_s1center_elem_num_ = std::accumulate(
+ stage1_center_out_dims.d + 1, stage1_center_out_dims.d + stage1_center_out_dims.nbDims, 1,
+ std::multiplies());
+ out_s1center_elem_num_ = out_s1center_elem_num_ * batch_config[2];
+ out_s1center_elem_num_per_batch_ = static_cast(out_s1center_elem_num_ / batch_config[2]);
+ out_s1center_prob_d_ = cuda_utils::make_unique(out_s1center_elem_num_);
+ out_s1center_prob_h_ =
+ cuda_utils::make_unique_host(out_s1center_elem_num_, cudaHostAllocPortable);
+
+ const auto pred_out_dims = trt_common_->getBindingDimensions(3);
+ out_pred_elem_num_ = std::accumulate(
+ pred_out_dims.d + 1, pred_out_dims.d + pred_out_dims.nbDims, 1, std::multiplies());
+ out_pred_elem_num_ = out_pred_elem_num_ * batch_config[2];
+ out_pred_elem_num_per_batch_ = static_cast(out_pred_elem_num_ / batch_config[2]);
+ out_pred_prob_d_ = cuda_utils::make_unique(out_pred_elem_num_);
+ out_pred_prob_h_ =
+ cuda_utils::make_unique_host(out_pred_elem_num_, cudaHostAllocPortable);
+
+ g_type_mean_size_ = {{4.6344314, 1.9600292, 1.7375569}, {6.936331, 2.5178623, 2.8506238},
+ {11.194943, 2.9501154, 3.4918275}, {12.275775, 2.9231303, 3.87086},
+ {0.80057803, 0.5983815, 1.27450867}, {1.76282397, 0.59706367, 1.73698127},
+ {16.17150617, 2.53246914, 3.53079012}, {3.64300781, 1.54298177, 1.92320313}};
+}
+
+bool TrtShapeEstimator::inference(
+ const DetectedObjectsWithFeature & input, DetectedObjectsWithFeature & output)
+{
+ if (!trt_common_->isInitialized()) {
+ return false;
+ }
+
+ bool result = false;
+
+ for (size_t i = 0; i < input.feature_objects.size(); i += batch_size_) {
+ DetectedObjectsWithFeature input_batch;
+ input_batch.header = input.header;
+
+ for (size_t j = 0; j < batch_size_ && (i + j) < input.feature_objects.size(); ++j) {
+ input_batch.feature_objects.push_back(input.feature_objects[i + j]);
+ }
+
+ preprocess(input_batch);
+ DetectedObjectsWithFeature output_batch;
+ result = feed_forward_and_decode(input_batch, output_batch);
+
+ output.feature_objects.insert(
+ output.feature_objects.end(), output_batch.feature_objects.begin(),
+ output_batch.feature_objects.end());
+ }
+
+ return result;
+}
+
+void TrtShapeEstimator::preprocess(const DetectedObjectsWithFeature & input)
+{
+ auto input_dims_pc = trt_common_->getBindingDimensions(0);
+ int batch_size = static_cast(input.feature_objects.size());
+
+ const auto input_chan = static_cast(input_dims_pc.d[1]);
+ const auto input_pc_size = static_cast(input_dims_pc.d[2]);
+
+ auto input_dims_one_hot = trt_common_->getBindingDimensions(1);
+ const auto input_one_hot_size = static_cast(input_dims_one_hot.d[1]);
+
+ int volume_pc = batch_size * input_chan * input_pc_size;
+ input_pc_h_.resize(volume_pc);
+
+ int volume_one_hot = batch_size * input_one_hot_size;
+ input_one_hot_h_.resize(volume_one_hot);
+
+ // fill point cloud
+ for (size_t i = 0; i < input.feature_objects.size(); i++) {
+ const auto & feature_object = input.feature_objects[i];
+
+ int point_size_of_cloud =
+ feature_object.feature.cluster.width * feature_object.feature.cluster.height;
+
+ if (point_size_of_cloud <= input_pc_size) {
+ int offset = 0;
+ for (sensor_msgs::PointCloud2ConstIterator x_iter(feature_object.feature.cluster, "x"),
+ y_iter(feature_object.feature.cluster, "y"), z_iter(feature_object.feature.cluster, "z");
+ x_iter != x_iter.end(); ++x_iter, ++y_iter, ++z_iter) {
+ input_pc_h_[i * input_chan * input_pc_size + 0 + offset] = -1 * (*y_iter);
+ input_pc_h_[i * input_chan * input_pc_size + 512 + offset] = -1 * (*z_iter);
+ input_pc_h_[i * input_chan * input_pc_size + 1024 + offset] = *x_iter;
+ offset++;
+ }
+
+ int iter_count = static_cast(input_pc_size) / point_size_of_cloud;
+ int remainer_count = static_cast(input_pc_size) % point_size_of_cloud;
+
+ for (int j = 1; j < iter_count; j++) {
+ for (int k = 0; k < point_size_of_cloud; k++) {
+ input_pc_h_[i * input_chan * input_pc_size + 0 + j * point_size_of_cloud + k] =
+ input_pc_h_[i * input_chan * input_pc_size + k];
+
+ input_pc_h_[i * input_chan * input_pc_size + 512 + j * point_size_of_cloud + k] =
+ input_pc_h_[i * input_chan * input_pc_size + 512 + k];
+
+ input_pc_h_[i * input_chan * input_pc_size + 1024 + j * point_size_of_cloud + k] =
+ input_pc_h_[i * input_chan * input_pc_size + 1024 + k];
+ }
+ }
+
+ for (int j = 0; j < remainer_count; j++) {
+ input_pc_h_[i * input_chan * input_pc_size + 0 + iter_count * point_size_of_cloud + j] =
+ input_pc_h_[i * input_chan * input_pc_size + j];
+
+ input_pc_h_[i * input_chan * input_pc_size + 512 + iter_count * point_size_of_cloud + j] =
+ input_pc_h_[i * input_chan * input_pc_size + 512 + j];
+
+ input_pc_h_[i * input_chan * input_pc_size + 1024 + iter_count * point_size_of_cloud + j] =
+ input_pc_h_[i * input_chan * input_pc_size + 1024 + j];
+ }
+
+ } else {
+ std::vector sampled_points;
+ std::vector indices(
+ feature_object.feature.cluster.width * feature_object.feature.cluster.height);
+ std::iota(indices.begin(), indices.end(), 0);
+
+ std::sample(
+ indices.begin(), indices.end(), std::back_inserter(sampled_points), 512,
+ std::mt19937{std::random_device{}()});
+
+ // Create an iterator to read the points
+ sensor_msgs::PointCloud2ConstIterator iter_x(feature_object.feature.cluster, "x");
+ sensor_msgs::PointCloud2ConstIterator iter_y(feature_object.feature.cluster, "y");
+ sensor_msgs::PointCloud2ConstIterator iter_z(feature_object.feature.cluster, "z");
+
+ int offset = 0;
+ for (const auto & index : sampled_points) {
+ auto idx = index * feature_object.feature.cluster.point_step / sizeof(float);
+ input_pc_h_[i * input_chan * input_pc_size + 0 + offset] = (-1 * iter_y[idx]);
+ input_pc_h_[i * input_chan * input_pc_size + 512 + offset] = (-1 * iter_z[idx]);
+ input_pc_h_[i * input_chan * input_pc_size + 1024 + offset] = iter_x[idx];
+ offset++;
+ }
+ }
+
+ const auto & label = feature_object.object.classification.front().label;
+
+ // Initialize all elements to 0.0f
+ input_one_hot_h_[i * 4 + 0] = 0.0f;
+ input_one_hot_h_[i * 4 + 1] = 0.0f;
+ input_one_hot_h_[i * 4 + 2] = 0.0f;
+ input_one_hot_h_[i * 4 + 3] = 0.0f;
+
+ if (label == Label::CAR) {
+ input_one_hot_h_[i * 4 + 0] = 1.0f;
+ } else if (label == Label::TRUCK) {
+ input_one_hot_h_[i * 4 + 1] = 1.0f;
+ } else if (label == Label::BUS) {
+ input_one_hot_h_[i * 4 + 2] = 1.0f;
+ } else if (label == Label::TRAILER) {
+ input_one_hot_h_[i * 4 + 3] = 1.0f;
+ }
+ }
+
+ CHECK_CUDA_ERROR(cudaMemcpy(
+ input_pc_d_.get(), input_pc_h_.data(), input_pc_h_.size() * sizeof(float),
+ cudaMemcpyHostToDevice));
+ CHECK_CUDA_ERROR(cudaMemcpy(
+ input_one_hot_d_.get(), input_one_hot_h_.data(), input_one_hot_h_.size() * sizeof(float),
+ cudaMemcpyHostToDevice));
+}
+
+bool TrtShapeEstimator::feed_forward_and_decode(
+ const DetectedObjectsWithFeature & input, DetectedObjectsWithFeature & output)
+{
+ int batch_size = static_cast(input.feature_objects.size());
+ std::vector buffers = {
+ input_pc_d_.get(), input_one_hot_d_.get(), out_s1center_prob_d_.get(), out_pred_prob_d_.get()};
+ trt_common_->enqueueV2(buffers.data(), *stream_, nullptr);
+
+ CHECK_CUDA_ERROR(cudaMemcpyAsync(
+ out_s1center_prob_h_.get(), out_s1center_prob_d_.get(), out_s1center_elem_num_ * sizeof(float),
+ cudaMemcpyDeviceToHost, *stream_));
+
+ CHECK_CUDA_ERROR(cudaMemcpyAsync(
+ out_pred_prob_h_.get(), out_pred_prob_d_.get(), out_pred_elem_num_ * sizeof(float),
+ cudaMemcpyDeviceToHost, *stream_));
+
+ cudaStreamSynchronize(*stream_);
+
+ float * out_stage1_net = out_s1center_prob_h_.get();
+ float * out_pred_net = out_pred_prob_h_.get();
+
+ output.feature_objects.resize(batch_size);
+ for (int i = 0; i < batch_size; i++) {
+ output.feature_objects.at(i) = input.feature_objects.at(i);
+
+ autoware_perception_msgs::msg::Shape shape;
+ geometry_msgs::msg::Pose pose;
+
+ shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX;
+
+ pose.position.x = out_stage1_net[i * out_s1center_elem_num_per_batch_ + 2] +
+ out_pred_net[i * out_pred_elem_num_per_batch_ + 2];
+ pose.position.y =
+ -(out_stage1_net[i * out_s1center_elem_num_per_batch_ + 0] +
+ out_pred_net[i * out_pred_elem_num_per_batch_ + 0]);
+ pose.position.z =
+ -(out_stage1_net[i * out_s1center_elem_num_per_batch_ + 1] +
+ out_pred_net[i * out_pred_elem_num_per_batch_ + 1]);
+
+ int idx = 0;
+ idx += 3;
+
+ int NUM_HEADING_BIN = 12;
+ int NUM_SIZE_CLUSTER = 8;
+
+ int heading_idx = 0;
+ float max = std::numeric_limits::lowest();
+ for (int j = idx; j < idx + NUM_HEADING_BIN; j++) {
+ if (out_pred_net[i * out_pred_elem_num_per_batch_ + j] > max) {
+ max = out_pred_net[i * out_pred_elem_num_per_batch_ + j];
+ heading_idx = j - idx;
+ }
+ }
+
+ idx += NUM_HEADING_BIN;
+
+ float heading_residual =
+ out_pred_net[i * out_pred_elem_num_per_batch_ + idx + heading_idx] * (M_PI / NUM_HEADING_BIN);
+
+ idx += NUM_HEADING_BIN;
+
+ float heading = class2angle(heading_idx, heading_residual, NUM_HEADING_BIN);
+
+ tf2::Quaternion quaternion;
+ quaternion.setRPY(0.0, 0.0, -M_PI / 2 - heading);
+
+ pose.orientation.x = quaternion.x();
+ pose.orientation.y = quaternion.y();
+ pose.orientation.z = quaternion.z();
+ pose.orientation.w = quaternion.w();
+
+ int size_idx = 0;
+ max = std::numeric_limits::lowest();
+ for (int j = idx; j < idx + NUM_SIZE_CLUSTER; j++) {
+ if (out_pred_net[i * out_pred_elem_num_per_batch_ + j] > max) {
+ max = out_pred_net[i * out_pred_elem_num_per_batch_ + j];
+ size_idx = j - idx;
+ }
+ }
+
+ idx += NUM_SIZE_CLUSTER;
+ float x_size = out_pred_net[i * out_pred_elem_num_per_batch_ + idx + size_idx * 3] *
+ g_type_mean_size_[size_idx][0] +
+ g_type_mean_size_[size_idx][0];
+
+ float y_size = out_pred_net[i * out_pred_elem_num_per_batch_ + idx + size_idx * 3 + 1] *
+ g_type_mean_size_[size_idx][1] +
+ g_type_mean_size_[size_idx][1];
+ float z_size = out_pred_net[i * out_pred_elem_num_per_batch_ + idx + size_idx * 3 + 2] *
+ g_type_mean_size_[size_idx][2] +
+ g_type_mean_size_[size_idx][2];
+
+ shape.dimensions.x = x_size;
+ shape.dimensions.y = y_size;
+ shape.dimensions.z = z_size;
+
+ output.feature_objects.at(i).object.shape = shape;
+ output.feature_objects.at(i).object.kinematics.pose_with_covariance.pose = pose;
+ }
+
+ return true;
+}
+
+double TrtShapeEstimator::class2angle(int pred_cls, double residual, int num_class)
+{
+ double angle_per_class = 2.0 * M_PI / static_cast(num_class);
+ double angle_center = static_cast(pred_cls) * angle_per_class;
+ double angle = angle_center + residual;
+
+ // Adjust angle to be within the range [-pi, pi]
+ while (angle > M_PI) {
+ angle -= 2.0 * M_PI;
+ }
+ while (angle < -M_PI) {
+ angle += 2.0 * M_PI;
+ }
+ return angle;
+};
+} // namespace autoware::shape_estimation
diff --git a/perception/autoware_shape_estimation/package.xml b/perception/autoware_shape_estimation/package.xml
index ad226a5cc2f66..fec1009428113 100644
--- a/perception/autoware_shape_estimation/package.xml
+++ b/perception/autoware_shape_estimation/package.xml
@@ -6,19 +6,27 @@
This package implements a shape estimation algorithm as a ROS 2 node
Yukihiro Saito
Yoshi Ri
+ Kaan Colak
Apache License 2.0
ament_cmake
autoware_cmake
+ cudnn_cmake_module
+ tensorrt_cmake_module
+
+ cudnn_cmake_module
+ tensorrt_cmake_module
autoware_perception_msgs
autoware_universe_utils
+ cuda_utils
eigen
libopencv-dev
libpcl-all-dev
pcl_conversions
rclcpp
rclcpp_components
+ tensorrt_common
tf2
tf2_eigen
tf2_geometry_msgs
diff --git a/perception/autoware_shape_estimation/schema/shape_estimation.schema.json b/perception/autoware_shape_estimation/schema/shape_estimation.schema.json
index d81bfa636a923..6a7e3d25af534 100644
--- a/perception/autoware_shape_estimation/schema/shape_estimation.schema.json
+++ b/perception/autoware_shape_estimation/schema/shape_estimation.schema.json
@@ -30,6 +30,37 @@
"type": "boolean",
"description": "The flag to use boost bbox optimizer",
"default": "false"
+ },
+ "model_params": {
+ "type": "object",
+ "description": "Parameters for model configuration.",
+ "properties": {
+ "use_ml_shape_estimator": {
+ "type": "boolean",
+ "description": "The flag to apply use ml bounding box estimator.",
+ "default": "true"
+ },
+ "minimum_points": {
+ "type": "integer",
+ "description": "The minimum number of points to fit a bounding box.",
+ "default": "16"
+ },
+ "precision": {
+ "type": "string",
+ "description": "The precision of the model.",
+ "default": "fp32"
+ },
+ "batch_size": {
+ "type": "integer",
+ "description": "The batch size of the model.",
+ "default": "32"
+ },
+ "build_only": {
+ "type": "boolean",
+ "description": "The flag to build the model only.",
+ "default": "false"
+ }
+ }
}
},
"required": [
diff --git a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp
index 4a373b15d580f..9c9c996ba0c6d 100644
--- a/perception/autoware_shape_estimation/src/shape_estimation_node.cpp
+++ b/perception/autoware_shape_estimation/src/shape_estimation_node.cpp
@@ -56,6 +56,23 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option
estimator_ =
std::make_unique(use_corrector, use_filter, use_boost_bbox_optimizer);
+#ifdef USE_CUDA
+ use_ml_shape_estimation_ = declare_parameter("model_params.use_ml_shape_estimator");
+ if (use_ml_shape_estimation_) {
+ std::string model_path = declare_parameter("model_path");
+ min_points_ = declare_parameter("model_params.minimum_points");
+ std::string precision = declare_parameter("model_params.precision");
+ int batch_size = declare_parameter("model_params.batch_size");
+ tensorrt_common::BatchConfig batch_config{batch_size, batch_size, batch_size};
+ tensorrt_shape_estimator_ =
+ std::make_unique(model_path, precision, batch_config);
+ if (this->declare_parameter("model_params.build_only", false)) {
+ RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node.");
+ rclcpp::shutdown();
+ }
+ }
+#endif
+
processing_time_publisher_ =
std::make_unique(this, "shape_estimation");
stop_watch_ptr_ =
@@ -94,6 +111,9 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared
DetectedObjectsWithFeature output_msg;
output_msg.header = input_msg->header;
+ // Create ml model input batch
+ DetectedObjectsWithFeature input_trt_batch;
+
// Estimate shape for each object and pack msg
for (const auto & feature_object : input_msg->feature_objects) {
const auto & object = feature_object.object;
@@ -109,6 +129,14 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared
continue;
}
+#ifdef USE_CUDA
+ // If ml based shape estimation is enabled, add object to input batch and continue
+ if (is_vehicle && use_ml_shape_estimation_ && cluster->size() > min_points_) {
+ input_trt_batch.feature_objects.push_back(feature_object);
+ continue;
+ }
+#endif
+
// estimate shape and pose
autoware_perception_msgs::msg::Shape shape;
geometry_msgs::msg::Pose pose;
@@ -138,6 +166,16 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared
output_msg.feature_objects.back().object.kinematics.pose_with_covariance.pose = pose;
}
+#ifdef USE_CUDA
+ DetectedObjectsWithFeature output_model;
+ if (use_ml_shape_estimation_ && !input_trt_batch.feature_objects.empty()) {
+ tensorrt_shape_estimator_->inference(input_trt_batch, output_model);
+ }
+ for (auto & feature_object : output_model.feature_objects) {
+ output_msg.feature_objects.push_back(feature_object);
+ }
+#endif
+
// Publish
pub_->publish(output_msg);
published_time_publisher_->publish_if_subscribed(pub_, output_msg.header.stamp);
diff --git a/perception/autoware_shape_estimation/src/shape_estimation_node.hpp b/perception/autoware_shape_estimation/src/shape_estimation_node.hpp
index d9f944346611a..a98d45453086b 100644
--- a/perception/autoware_shape_estimation/src/shape_estimation_node.hpp
+++ b/perception/autoware_shape_estimation/src/shape_estimation_node.hpp
@@ -17,6 +17,12 @@
#include "autoware/shape_estimation/shape_estimator.hpp"
+#ifdef USE_CUDA
+#include "autoware/shape_estimation/tensorrt_shape_estimator.hpp"
+
+#include
+#endif
+
#include
#include
#include
@@ -51,6 +57,13 @@ class ShapeEstimationNode : public rclcpp::Node
bool use_vehicle_reference_shape_size_;
bool fix_filtered_objects_label_to_unknown_;
+#ifdef USE_CUDA
+ std::unique_ptr tensorrt_shape_estimator_;
+#endif
+
+ bool use_ml_shape_estimation_;
+ size_t min_points_;
+
public:
explicit ShapeEstimationNode(const rclcpp::NodeOptions & node_options);
};
diff --git a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp
index 98b368ff373e8..19d3fb3036471 100644
--- a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp
+++ b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp
@@ -123,7 +123,6 @@ TrtClassifier::TrtClassifier(
autoware::tensorrt_classifier::ImageStream stream(
max_batch_size, input_dims, calibration_images);
fs::path calibration_table{model_path};
- std::string calibName = "";
std::string ext = "";
if (build_config.calib_type_str == "Entropy") {
ext = "EntropyV2-";
diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp
index 1d468f7a647a5..4b12a8e19c31f 100644
--- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp
+++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp
@@ -186,7 +186,6 @@ TrtYoloX::TrtYoloX(
}
tensorrt_yolox::ImageStream stream(max_batch_size, input_dims, calibration_images);
fs::path calibration_table{model_path};
- std::string calibName = "";
std::string ext = "";
if (build_config.calib_type_str == "Entropy") {
ext = "EntropyV2-";
diff --git a/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp b/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp
index 6e3ae34297510..7a6d00f0135c5 100644
--- a/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp
+++ b/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.cpp
@@ -195,7 +195,7 @@ bool CNNClassifier::readLabelfile(std::string filepath, std::vector
return true;
}
-bool CNNClassifier::isColorLabel(const std::string label)
+bool CNNClassifier::isColorLabel(const std::string & label)
{
using tier4_perception_msgs::msg::TrafficLight;
if (
diff --git a/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.hpp b/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.hpp
index 5f6f086763f4e..85895cfc9e637 100644
--- a/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.hpp
+++ b/perception/autoware_traffic_light_classifier/src/classifier/cnn_classifier.hpp
@@ -63,7 +63,7 @@ class CNNClassifier : public ClassifierInterface
void postProcess(
int class_index, float prob, tier4_perception_msgs::msg::TrafficLight & traffic_signal);
bool readLabelfile(std::string filepath, std::vector & labels);
- bool isColorLabel(const std::string label);
+ bool isColorLabel(const std::string & label);
void outputDebugImage(
cv::Mat & debug_image, const tier4_perception_msgs::msg::TrafficLight & traffic_signal);
diff --git a/perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp b/perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp
index b42ded4cbffa3..88c15c7c457eb 100644
--- a/perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp
+++ b/perception/autoware_traffic_light_classifier/src/traffic_light_classifier_node.cpp
@@ -84,6 +84,9 @@ void TrafficLightClassifierNodelet::imageRoiCallback(
if (classifier_ptr_.use_count() == 0) {
return;
}
+ if (input_rois_msg->rois.empty()) {
+ return;
+ }
cv_bridge::CvImagePtr cv_ptr;
try {
@@ -95,41 +98,49 @@ void TrafficLightClassifierNodelet::imageRoiCallback(
}
tier4_perception_msgs::msg::TrafficLightArray output_msg;
-
output_msg.signals.resize(input_rois_msg->rois.size());
std::vector images;
std::vector backlight_indices;
- for (size_t i = 0; i < input_rois_msg->rois.size(); i++) {
- // skip if the roi is not detected
- if (input_rois_msg->rois.at(i).roi.height == 0) {
- break;
+ size_t idx_valid_roi = 0;
+ for (const auto & input_roi : input_rois_msg->rois) {
+ // ignore if the roi is not the type to be classified
+ if (input_roi.traffic_light_type != classify_traffic_light_type_) {
+ continue;
}
- if (input_rois_msg->rois.at(i).traffic_light_type != classify_traffic_light_type_) {
+ // skip if the roi size is zero
+ if (input_roi.roi.height == 0 || input_roi.roi.width == 0) {
continue;
}
- output_msg.signals[images.size()].traffic_light_id =
- input_rois_msg->rois.at(i).traffic_light_id;
- output_msg.signals[images.size()].traffic_light_type =
- input_rois_msg->rois.at(i).traffic_light_type;
- const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi;
+ // set traffic light id and type
+ output_msg.signals[idx_valid_roi].traffic_light_id = input_roi.traffic_light_id;
+ output_msg.signals[idx_valid_roi].traffic_light_type = input_roi.traffic_light_type;
+
+ const sensor_msgs::msg::RegionOfInterest & roi = input_roi.roi;
auto roi_img = cv_ptr->image(cv::Rect(roi.x_offset, roi.y_offset, roi.width, roi.height));
if (is_harsh_backlight(roi_img)) {
- backlight_indices.emplace_back(i);
+ backlight_indices.emplace_back(idx_valid_roi);
}
images.emplace_back(roi_img);
+ idx_valid_roi++;
}
+ // classify the images
output_msg.signals.resize(images.size());
- if (!classifier_ptr_->getTrafficSignals(images, output_msg)) {
- RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback");
- return;
+ if (!images.empty()) {
+ if (!classifier_ptr_->getTrafficSignals(images, output_msg)) {
+ RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback");
+ return;
+ }
}
// append the undetected rois as unknown
for (const auto & input_roi : input_rois_msg->rois) {
- if (input_roi.roi.height == 0 && input_roi.traffic_light_type == classify_traffic_light_type_) {
+ // if the type is the target type but the roi size is zero, the roi is undetected
+ if (
+ (input_roi.roi.height == 0 || input_roi.roi.width == 0) &&
+ input_roi.traffic_light_type == classify_traffic_light_type_) {
tier4_perception_msgs::msg::TrafficLight tlr_sig;
tlr_sig.traffic_light_id = input_roi.traffic_light_id;
tlr_sig.traffic_light_type = input_roi.traffic_light_type;
diff --git a/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.cpp b/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.cpp
index 74878ba0b93af..7fd5ac8489226 100644
--- a/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.cpp
+++ b/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.cpp
@@ -148,7 +148,7 @@ void CloudOcclusionPredictor::calcRoiVector3D(
void CloudOcclusionPredictor::filterCloud(
const pcl::PointCloud & cloud_in, const std::vector & roi_tls,
- const std::vector & roi_brs, pcl::PointCloud & cloud_out)
+ const std::vector & roi_brs, pcl::PointCloud & cloud_out) const
{
float min_x = 0, max_x = 0, min_y = 0, max_y = 0, min_z = 0, max_z = 0;
for (const auto & pt : roi_tls) {
diff --git a/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.hpp b/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.hpp
index 435ee478eea22..701b15f7c92b8 100644
--- a/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.hpp
+++ b/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.hpp
@@ -73,7 +73,7 @@ class CloudOcclusionPredictor
void filterCloud(
const pcl::PointCloud & cloud_in, const std::vector & roi_tls,
- const std::vector & roi_brs, pcl::PointCloud & cloud_out);
+ const std::vector & roi_brs, pcl::PointCloud & cloud_out) const;
void sampleTrafficLightRoi(
const pcl::PointXYZ & top_left, const pcl::PointXYZ & bottom_right,
diff --git a/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp b/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp
index 90b73e643ae8e..ccfaf37fd7c6d 100644
--- a/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp
+++ b/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.cpp
@@ -38,7 +38,7 @@ namespace
}
bool isAttributeValue(
- const lanelet::ConstPoint3d p, const std::string attr_str, const std::string value_str)
+ const lanelet::ConstPoint3d p, const std::string & attr_str, const std::string & value_str)
{
lanelet::Attribute attr = p.attribute(attr_str);
if (attr.value().compare(value_str) == 0) {
@@ -49,7 +49,7 @@ bool isAttributeValue(
void lightAsMarker(
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & node_logging,
- lanelet::ConstPoint3d p, visualization_msgs::msg::Marker * marker, const std::string ns,
+ lanelet::ConstPoint3d p, visualization_msgs::msg::Marker * marker, const std::string & ns,
const rclcpp::Time & current_time)
{
if (marker == nullptr) {
diff --git a/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.hpp b/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.hpp
index 61b5204b57592..1870a2b1bf74f 100644
--- a/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.hpp
+++ b/perception/autoware_traffic_light_visualization/src/traffic_light_map_visualizer/node.hpp
@@ -31,11 +31,11 @@ namespace autoware::traffic_light
class TrafficLightMapVisualizerNode : public rclcpp::Node
{
public:
- explicit TrafficLightMapVisualizerNode(const rclcpp::NodeOptions & options);
+ explicit TrafficLightMapVisualizerNode(const rclcpp::NodeOptions & node_options);
~TrafficLightMapVisualizerNode() = default;
void trafficSignalsCallback(
const autoware_perception_msgs::msg::TrafficLightGroupArray::ConstSharedPtr
- input_traffic_signals_msg);
+ input_traffic_signals);
void binMapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_map_msg);
private:
diff --git a/perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/shape_draw.cpp b/perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/shape_draw.cpp
index c44b1415a09dc..c685bc0639601 100644
--- a/perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/shape_draw.cpp
+++ b/perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/shape_draw.cpp
@@ -52,7 +52,10 @@ void drawShape(
if (
position.x < 0 || position.y < 0 || position.x + shapeImg.cols > params.image.cols ||
position.y + shapeImg.rows > params.image.rows) {
- std::cerr << "Adjusted position is out of image bounds." << std::endl;
+ // TODO(KhalilSelyan): This error message may flood the terminal logs, so commented out
+ // temporarily. Need to consider a better way.
+
+ // std::cerr << "Adjusted position is out of image bounds." << std::endl;
return;
}
diff --git a/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp
index 7b4c8e3856b38..f43b4401865b2 100644
--- a/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp
+++ b/planning/autoware_freespace_planner/test/test_freespace_planner_node_interface.cpp
@@ -60,7 +60,8 @@ void publishMandatoryTopics(
test_manager->publishParkingScenario(test_target_node, "freespace_planner/input/scenario");
}
-TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInput)
+// the following tests are disable because they randomly fail
+TEST(PlanningModuleInterfaceTest, DISABLED_testPlanningInterfaceWithVariousTrajectoryInput)
{
rclcpp::init(0, nullptr);
@@ -77,7 +78,7 @@ TEST(PlanningModuleInterfaceTest, testPlanningInterfaceWithVariousTrajectoryInpu
rclcpp::shutdown();
}
-TEST(PlanningModuleInterfaceTest, NodeTestWithOffTrackEgoPose)
+TEST(PlanningModuleInterfaceTest, DISABLED_NodeTestWithOffTrackEgoPose)
{
rclcpp::init(0, nullptr);
auto test_manager = generateTestManager();
diff --git a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/astar_search.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/astar_search.hpp
index 3f6c3935b8a42..f7434d912d5e0 100644
--- a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/astar_search.hpp
+++ b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/astar_search.hpp
@@ -79,7 +79,7 @@ struct AstarNode
struct NodeComparison
{
- bool operator()(const AstarNode * lhs, const AstarNode * rhs) { return lhs->fc > rhs->fc; }
+ bool operator()(const AstarNode * lhs, const AstarNode * rhs) const { return lhs->fc > rhs->fc; }
};
struct NodeUpdate
diff --git a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp
index 4ead3cb5a7423..9233ad212bfa5 100644
--- a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp
+++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp
@@ -155,7 +155,7 @@ void AstarSearch::setCollisionFreeDistanceMap()
using Entry = std::pair;
struct CompareEntry
{
- bool operator()(const Entry & a, const Entry & b) { return a.second > b.second; }
+ bool operator()(const Entry & a, const Entry & b) const { return a.second > b.second; }
};
std::priority_queue, CompareEntry> heap;
std::vector closed(col_free_distance_map_.size(), false);
diff --git a/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp b/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp
index 82d8a5abcee8c..97149dbbb071f 100644
--- a/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp
+++ b/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp
@@ -208,10 +208,8 @@ void CSC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath &
ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[13], t, u, v);
L_min = L;
}
- if (
- LpSpRp(-x, -y, phi, t, u, v) &&
- L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect
- {
+ // time flip + reflect
+ if (LpSpRp(-x, -y, phi, t, u, v) && L_min > (std::abs(t) + std::abs(u) + std::abs(v))) {
path = ReedsSheppStateSpace::ReedsSheppPath(
ReedsSheppStateSpace::reedsSheppPathType[13], -t, -u, -v);
}
@@ -288,7 +286,7 @@ void CCC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath &
}
if (
LpRmL(-xb, -yb, phi, t, u, v) &&
- L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect
+ L_min > (std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect
{
path =
ReedsSheppStateSpace::ReedsSheppPath(ReedsSheppStateSpace::reedsSheppPathType[1], -v, -u, -t);
@@ -387,7 +385,7 @@ void CCCC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath &
}
if (
LpRumLumRp(-x, -y, phi, t, u, v) &&
- L_min > (L = std::abs(t) + 2. * std::abs(u) + std::abs(v))) // time flip + reflect
+ L_min > (std::abs(t) + 2. * std::abs(u) + std::abs(v))) // time flip + reflect
{
path = ReedsSheppStateSpace::ReedsSheppPath(
ReedsSheppStateSpace::reedsSheppPathType[3], -t, -u, -u, -v);
@@ -545,7 +543,7 @@ void CCSC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath &
}
if (
LpRmSmRm(-xb, -yb, phi, t, u, v) &&
- L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect
+ L_min > (std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect
{
path = ReedsSheppStateSpace::ReedsSheppPath(
ReedsSheppStateSpace::reedsSheppPathType[11], -v, -u, .5 * pi, -t);
@@ -598,7 +596,7 @@ void CCSCC(double x, double y, double phi, ReedsSheppStateSpace::ReedsSheppPath
}
if (
LpRmSLmRp(-x, -y, phi, t, u, v) &&
- L_min > (L = std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect
+ L_min > (std::abs(t) + std::abs(u) + std::abs(v))) // time flip + reflect
{
path = ReedsSheppStateSpace::ReedsSheppPath(
ReedsSheppStateSpace::reedsSheppPathType[17], -t, .5 * pi, -u, .5 * pi, -v);
diff --git a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp
index c5fcf29466936..ee2eadac6f780 100644
--- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp
+++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp
@@ -605,7 +605,7 @@ double AdaptiveCruiseController::calcBaseDistToForwardObstacle(
}
double AdaptiveCruiseController::calcTargetVelocity_P(
- const double target_dist, const double current_dist)
+ const double target_dist, const double current_dist) const
{
const double diff_dist = current_dist - target_dist;
double add_vel_p;
@@ -748,7 +748,7 @@ void AdaptiveCruiseController::registerQueToVelocity(
est_vel_que_.emplace_back(new_vel);
}
-double AdaptiveCruiseController::getMedianVel(const std::vector vel_que)
+double AdaptiveCruiseController::getMedianVel(const std::vector & vel_que)
{
if (vel_que.size() == 0) {
RCLCPP_WARN_STREAM(node_->get_logger(), "size of vel que is 0. Something has wrong.");
diff --git a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp
index 586866f9a94d6..7535986f1db85 100644
--- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp
+++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp
@@ -183,14 +183,15 @@ class AdaptiveCruiseController
};
Param param_;
- double getMedianVel(const std::vector vel_que);
- double lowpass_filter(const double current_value, const double prev_value, const double gain);
+ double getMedianVel(const std::vector & vel_que);
+ static double lowpass_filter(
+ const double current_value, const double prev_value, const double gain);
void calcDistanceToNearestPointOnPath(
const TrajectoryPoints & trajectory, const int nearest_point_idx,
const geometry_msgs::msg::Pose & self_pose, const pcl::PointXYZ & nearest_collision_point,
const rclcpp::Time & nearest_collision_point_time, double * distance,
const std_msgs::msg::Header & trajectory_header);
- double calcTrajYaw(const TrajectoryPoints & trajectory, const int collision_point_idx);
+ static double calcTrajYaw(const TrajectoryPoints & trajectory, const int collision_point_idx);
std::optional estimatePointVelocityFromObject(
const autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr object_ptr,
const double traj_yaw, const pcl::PointXYZ & nearest_collision_point);
@@ -204,8 +205,8 @@ class AdaptiveCruiseController
double calcUpperVelocity(const double dist_to_col, const double obj_vel, const double self_vel);
double calcThreshDistToForwardObstacle(const double current_vel, const double obj_vel);
double calcBaseDistToForwardObstacle(const double current_vel, const double obj_vel);
- double calcTargetVelocity_P(const double target_dist, const double current_dist);
- double calcTargetVelocity_I(const double target_dist, const double current_dist);
+ double calcTargetVelocity_P(const double target_dist, const double current_dist) const;
+ static double calcTargetVelocity_I(const double target_dist, const double current_dist);
double calcTargetVelocity_D(const double target_dist, const double current_dist);
double calcTargetVelocityByPID(
const double current_vel, const double current_dist, const double obj_vel);
diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp
index 4fc8386e92b44..1b4cdfd87f81b 100644
--- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp
+++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp
@@ -78,7 +78,7 @@ class DebugValues
* @param [in] type the TYPE enum for which to get the index
* @return index of the type
*/
- int getValuesIdx(const TYPE type) const { return static_cast(type); }
+ static int getValuesIdx(const TYPE type) { return static_cast(type); }
/**
* @brief get all the debug values as an std::array
* @return array of all debug values
diff --git a/planning/autoware_obstacle_stop_planner/src/planner_utils.cpp b/planning/autoware_obstacle_stop_planner/src/planner_utils.cpp
index bff8f9588215e..28c5523f49620 100644
--- a/planning/autoware_obstacle_stop_planner/src/planner_utils.cpp
+++ b/planning/autoware_obstacle_stop_planner/src/planner_utils.cpp
@@ -228,7 +228,7 @@ std::string jsonDumpsPose(const Pose & pose)
return json_dumps_pose;
}
-DiagnosticStatus makeStopReasonDiag(const std::string stop_reason, const Pose & stop_pose)
+DiagnosticStatus makeStopReasonDiag(const std::string & stop_reason, const Pose & stop_pose)
{
DiagnosticStatus stop_reason_diag;
KeyValue stop_reason_diag_kv;
diff --git a/planning/autoware_obstacle_stop_planner/src/planner_utils.hpp b/planning/autoware_obstacle_stop_planner/src/planner_utils.hpp
index 21943c46f5ca5..228c71d08a9b9 100644
--- a/planning/autoware_obstacle_stop_planner/src/planner_utils.hpp
+++ b/planning/autoware_obstacle_stop_planner/src/planner_utils.hpp
@@ -122,7 +122,7 @@ Polygon2d convertBoundingBoxObjectToGeometryPolygon(
std::string jsonDumpsPose(const Pose & pose);
-DiagnosticStatus makeStopReasonDiag(const std::string stop_reason, const Pose & stop_pose);
+DiagnosticStatus makeStopReasonDiag(const std::string & stop_reason, const Pose & stop_pose);
TrajectoryPoint getBackwardPointFromBasePoint(
const TrajectoryPoint & p_from, const TrajectoryPoint & p_to, const TrajectoryPoint & p_base,
diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp
index 45943d7deec09..367fc915badba 100644
--- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp
+++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp
@@ -1434,6 +1434,7 @@ MPTOptimizer::ConstraintMatrix MPTOptimizer::calcConstraintMatrix(
ub(A_rows_end + i) = ref_steer_angle + mpt_param_.max_steer_rad;
}
+ // cppcheck-suppress unreadVariable
A_rows_end += N_u;
}
diff --git a/planning/autoware_route_handler/src/route_handler.cpp b/planning/autoware_route_handler/src/route_handler.cpp
index 9811f982f8e1b..f10b480a5e234 100644
--- a/planning/autoware_route_handler/src/route_handler.cpp
+++ b/planning/autoware_route_handler/src/route_handler.cpp
@@ -2143,6 +2143,14 @@ bool RouteHandler::planPathLaneletsBetweenCheckpoints(
continue;
}
is_route_found = true;
+ lanelet::ConstLanelet preferred_lane{};
+ if (getClosestPreferredLaneletWithinRoute(start_checkpoint, &preferred_lane)) {
+ if (st_llt.id() == preferred_lane.id()) {
+ shortest_path = optional_route->shortestPath();
+ start_lanelet = st_llt;
+ break;
+ }
+ }
if (angle_diff < smallest_angle_diff) {
smallest_angle_diff = angle_diff;
shortest_path = optional_route->shortestPath();
diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp
index 541ba62e95d74..0640bc950f411 100644
--- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp
+++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.hpp
@@ -45,8 +45,8 @@ bool calcStopVelocityWithConstantJerkAccLimit(
const std::vector & times, const size_t start_index,
TrajectoryPoints & output_trajectory);
void updateStopVelocityStatus(
- double v0, double a0, double jerk_acc, double jerk_dec, int type, std::vector times,
- double t, double & x, double & v, double & a, double & j);
+ double v0, double a0, double jerk_acc, double jerk_dec, int type,
+ const std::vector & times, double t, double & x, double & v, double & a, double & j);
double integ_x(double x0, double v0, double a0, double j0, double t);
double integ_v(double v0, double a0, double j0, double t);
double integ_a(double a0, double j0, double t);
diff --git a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp
index 739ba6e7cef38..9d474a9a52bfa 100644
--- a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp
+++ b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/velocity_planning_utils.cpp
@@ -271,8 +271,8 @@ bool calcStopVelocityWithConstantJerkAccLimit(
}
void updateStopVelocityStatus(
- double v0, double a0, double jerk_acc, double jerk_dec, int type, std::vector times,
- double t, double & x, double & v, double & a, double & j)
+ double v0, double a0, double jerk_acc, double jerk_dec, int type,
+ const std::vector & times, double t, double & x, double & v, double & a, double & j)
{
if (type == 1) {
if (0 <= t && t < times.at(0)) {
diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp
index 9c85a463067de..f09196b2cc8e1 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/manager.hpp
@@ -47,8 +47,6 @@ class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface
void updateModuleParams(const std::vector & parameters) override;
- bool isAlwaysExecutableModule() const override;
-
private:
std::shared_ptr parameters_;
};
diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp
index eccf2b2a1bfde..cdf878fb62c63 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/manager.cpp
@@ -287,10 +287,6 @@ void DynamicObstacleAvoidanceModuleManager::updateModuleParams(
});
}
-bool DynamicObstacleAvoidanceModuleManager::isAlwaysExecutableModule() const
-{
- return true;
-}
} // namespace autoware::behavior_path_planner
#include
diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp
index 32d816d9a37e8..5408dce9dcdfc 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/manager.hpp
@@ -43,8 +43,6 @@ class GoalPlannerModuleManager : public SceneModuleManagerInterface
void updateModuleParams(const std::vector & parameters) override;
- bool isAlwaysExecutableModule() const override;
-
bool isSimultaneousExecutableAsApprovedModule() const override;
bool isSimultaneousExecutableAsCandidateModule() const override;
diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp
index 8a4f3ab202a67..00b27d43087f5 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/manager.cpp
@@ -827,23 +827,8 @@ void GoalPlannerModuleManager::updateModuleParams(
});
}
-bool GoalPlannerModuleManager::isAlwaysExecutableModule() const
-{
- // enable AlwaysExecutable whenever goal modification is not allowed
- // because only minor path refinements are made for fixed goals
- if (!utils::isAllowedGoalModification(planner_data_->route_handler)) {
- return true;
- }
-
- return false;
-}
-
bool GoalPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const
{
- if (isAlwaysExecutableModule()) {
- return true;
- }
-
// enable SimultaneousExecutable whenever goal modification is not allowed
// because only minor path refinements are made for fixed goals
if (!utils::isAllowedGoalModification(planner_data_->route_handler)) {
@@ -855,10 +840,6 @@ bool GoalPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const
bool GoalPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() const
{
- if (isAlwaysExecutableModule()) {
- return true;
- }
-
// enable SimultaneousExecutable whenever goal modification is not allowed
// because only minor path refinements are made for fixed goals
if (!utils::isAllowedGoalModification(planner_data_->route_handler)) {
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt
index b0d9967e65ddd..509f38d52dd45 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CMakeLists.txt
@@ -9,6 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
src/interface.cpp
src/manager.cpp
src/scene.cpp
+ src/utils/calculation.cpp
src/utils/markers.cpp
src/utils/utils.cpp
)
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md
index 63f5a2ec05bf1..e42e6e2d47738 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md
@@ -618,6 +618,61 @@ The last behavior will also occur if the ego vehicle has departed from the curre
![stop](./images/lane_change-cant_cancel_no_abort.png)
+## Lane change completion checks
+
+To determine if the ego vehicle has successfully changed lanes, one of two criteria must be met: either the longitudinal or the lateral criteria.
+
+For the longitudinal criteria, the ego vehicle must pass the lane-changing end pose and be within the `finish_judge_buffer` distance from it. The module then checks if the ego vehicle is in the target lane. If true, the module returns success. This check ensures that the planner manager updates the root lanelet correctly based on the ego vehicle's current pose. Without this check, if the ego vehicle is changing lanes while avoiding an obstacle and its current pose is in the original lane, the planner manager might set the root lanelet as the original lane. This would force the ego vehicle to perform the lane change again. With the target lane check, the ego vehicle is confirmed to be in the target lane, and the planner manager can correctly update the root lanelets.
+
+If the longitudinal criteria are not met, the module evaluates the lateral criteria. For the lateral criteria, the ego vehicle must be within `finish_judge_lateral_threshold` distance from the target lane's centerline, and the angle deviation must be within `finish_judge_lateral_angle_deviation` degrees. The angle deviation check ensures there is no sudden steering. If the angle deviation is set too high, the ego vehicle's orientation could deviate significantly from the centerline, causing the trajectory follower to aggressively correct the steering to return to the centerline. Keeping the angle deviation value as small as possible avoids this issue.
+
+The process of determining lane change completion is shown in the following diagram.
+
+```plantuml
+@startuml
+skinparam defaultTextAlignment center
+skinparam backgroundColor #WHITE
+
+title Lane change completion judge
+
+start
+
+:Calculate distance from current ego pose to lane change end pose;
+
+if (Is ego velocity < 1.0?) then (YES)
+ :Set finish_judge_buffer to 0.0;
+else (NO)
+ :Set finish_judge_buffer to lane_change_finish_judge_buffer;
+endif
+
+if (ego has passed the end_pose and ego is finish_judge_buffer meters away from end_pose?) then (YES)
+ if (Current ego pose is in target lanes' polygon?) then (YES)
+ :Lane change is completed;
+ stop
+ else (NO)
+:Lane change is NOT completed;
+stop
+ endif
+else (NO)
+endif
+
+if (ego's yaw deviation to centerline exceeds finish_judge_lateral_angle_deviation?) then (YES)
+ :Lane change is NOT completed;
+ stop
+else (NO)
+ :Calculate distance to the target lanes' centerline;
+ if (abs(distance to the target lanes' centerline) is less than finish_judge_lateral_threshold?) then (YES)
+ :Lane change is completed;
+ stop
+ else (NO)
+ :Lane change is NOT completed;
+ stop
+ endif
+endif
+
+@enduml
+```
+
## Parameters
### Essential lane change parameters
@@ -631,7 +686,6 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi
| `backward_length_buffer_for_end_of_lane` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change | 3.0 |
| `backward_length_buffer_for_blocking_object` | [m] | double | The end of lane buffer to ensure ego vehicle has enough distance to start lane change when there is an object in front | 3.0 |
| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 2.0 |
-| `finish_judge_lateral_threshold` | [m] | double | Lateral distance threshold to confirm lane change process completion | 0.2 |
| `lane_changing_lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 |
| `minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 |
| `prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 |
@@ -647,6 +701,16 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi
| `lateral_acceleration.min_values` | [m/ss] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] |
| `lateral_acceleration.max_values` | [m/ss] | double | Max lateral acceleration values corresponding to velocity (look up table) | [0.65, 0.65, 0.65] |
+### Parameter to judge if lane change is completed
+
+The following parameters are used to judge lane change completion.
+
+| Name | Unit | Type | Description | Default value |
+| :------------------------------------- | ----- | ------ | ---------------------------------------------------------------------------------------------------------------------- | ------------- |
+| `lane_change_finish_judge_buffer` | [m] | double | The longitudinal distance starting from the lane change end pose. | 2.0 |
+| `finish_judge_lateral_threshold` | [m] | double | The lateral distance from targets lanes' centerline. Used in addition with `finish_judge_lateral_angle_deviation` | 0.1 |
+| `finish_judge_lateral_angle_deviation` | [deg] | double | Ego angle deviation with reference to target lanes' centerline. Used in addition with `finish_judge_lateral_threshold` | 2.0 |
+
### Lane change regulations
| Name | Unit | Type | Description | Default value |
@@ -709,6 +773,18 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi
| `safety_check.execution.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 |
| `safety_check.cancel.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 |
+#### safety constraints specifically for stopped or parked vehicles
+
+| Name | Unit | Type | Description | Default value |
+| :-------------------------------------------------------- | ------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- |
+| `safety_check.parked.expected_front_deceleration` | [m/s^2] | double | The front object's maximum deceleration when the front vehicle perform sudden braking. (\*1) | -1.0 |
+| `safety_check.parked.expected_rear_deceleration` | [m/s^2] | double | The rear object's maximum deceleration when the rear vehicle perform sudden braking. (\*1) | -2.0 |
+| `safety_check.parked.rear_vehicle_reaction_time` | [s] | double | The reaction time of the rear vehicle driver which starts from the driver noticing the sudden braking of the front vehicle until the driver step on the brake. | 1.0 |
+| `safety_check.parked.rear_vehicle_safety_time_margin` | [s] | double | The time buffer for the rear vehicle to come into complete stop when its driver perform sudden braking. | 0.8 |
+| `safety_check.parked.lateral_distance_max_threshold` | [m] | double | The lateral distance threshold that is used to determine whether lateral distance between two object is enough and whether lane change is safe. | 1.0 |
+| `safety_check.parked.longitudinal_distance_min_threshold` | [m] | double | The longitudinal distance threshold that is used to determine whether longitudinal distance between two object is enough and whether lane change is safe. | 3.0 |
+| `safety_check.parked.longitudinal_velocity_delta_time` | [m] | double | The time multiplier that is used to compute the actual gap between vehicle at each predicted points (not RSS distance) | 0.8 |
+
##### safety constraints to cancel lane change path
| Name | Unit | Type | Description | Default value |
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml
index d2f695071649a..7a9c466fec260 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/config/lane_change.param.yaml
@@ -6,7 +6,6 @@
backward_length_buffer_for_end_of_lane: 3.0 # [m]
backward_length_buffer_for_blocking_object: 3.0 # [m]
- lane_change_finish_judge_buffer: 2.0 # [m]
lane_changing_lateral_jerk: 0.5 # [m/s3]
@@ -39,6 +38,14 @@
lateral_distance_max_threshold: 2.0
longitudinal_distance_min_threshold: 3.0
longitudinal_velocity_delta_time: 0.8
+ parked:
+ expected_front_deceleration: -1.0
+ expected_rear_deceleration: -2.0
+ rear_vehicle_reaction_time: 1.0
+ rear_vehicle_safety_time_margin: 0.8
+ lateral_distance_max_threshold: 1.0
+ longitudinal_distance_min_threshold: 3.0
+ longitudinal_velocity_delta_time: 0.0
cancel:
expected_front_deceleration: -1.0
expected_rear_deceleration: -2.0
@@ -109,7 +116,9 @@
overhang_tolerance: 0.0 # [m]
unsafe_hysteresis_threshold: 10 # [/]
- finish_judge_lateral_threshold: 0.2 # [m]
+ lane_change_finish_judge_buffer: 2.0 # [m]
+ finish_judge_lateral_threshold: 0.1 # [m]
+ finish_judge_lateral_angle_deviation: 1.0 # [deg]
# debug
publish_debug_marker: false
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp
index a1284f355a87d..605e0499adcdb 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/scene.hpp
@@ -184,6 +184,24 @@ class NormalLaneChange : public LaneChangeBase
bool isVehicleStuck(const lanelet::ConstLanelets & current_lanes) const;
+ /**
+ * @brief Checks if the given pose is a valid starting point for a lane change.
+ *
+ * This function determines whether the given pose (position) of the vehicle is within
+ * the area of either the target neighbor lane or the target lane itself. It uses geometric
+ * checks to see if the start point of the lane change is covered by the polygons representing
+ * these lanes.
+ *
+ * @param common_data_ptr Shared pointer to a CommonData structure, which should include:
+ * - Non-null `lanes_polygon_ptr` that contains the polygon data for lanes.
+ * @param pose The current pose of the vehicle
+ *
+ * @return `true` if the pose is within either the target neighbor lane or the target lane;
+ * `false` otherwise.
+ */
+ bool is_valid_start_point(
+ const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) const;
+
bool check_prepare_phase() const;
double calcMaximumLaneChangeLength(
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp
new file mode 100644
index 0000000000000..421b54db9f67a
--- /dev/null
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp
@@ -0,0 +1,45 @@
+// Copyright 2024 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+#ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_
+#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_
+
+#include "autoware/behavior_path_lane_change_module/utils/data_structs.hpp"
+
+namespace autoware::behavior_path_planner::utils::lane_change::calculation
+{
+using behavior_path_planner::lane_change::CommonDataPtr;
+
+/**
+ * @brief Calculates the distance from the ego vehicle to the terminal point.
+ *
+ * This function computes the distance from the current position of the ego vehicle
+ * to either the goal pose or the end of the current lane, depending on whether
+ * the vehicle's current lane is within the goal section.
+ *
+ * @param common_data_ptr Shared pointer to a CommonData structure, which should include:
+ * - Non null `lanes_ptr` that points to the current lanes data.
+ * - Non null `self_odometry_ptr` that contains the current pose of the ego vehicle.
+ * - Non null `route_handler_ptr` that contains the goal pose of the route.
+ *
+ * @return The distance to the terminal point (either the goal pose or the end of the current lane)
+ * in meters.
+ */
+double calc_ego_dist_to_terminal_end(const CommonDataPtr & common_data_ptr);
+
+double calc_dist_from_pose_to_terminal_end(
+ const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & lanes,
+ const Pose & src_pose);
+} // namespace autoware::behavior_path_planner::utils::lane_change::calculation
+
+#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp
index 495fe9012ecd0..7962c878d7d64 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/data_structs.hpp
@@ -19,6 +19,7 @@
#include
#include
+#include
#include
#include
@@ -109,7 +110,6 @@ struct Parameters
double lane_changing_lateral_jerk{0.5};
double minimum_lane_changing_velocity{5.6};
double lane_change_prepare_duration{4.0};
- double lane_change_finish_judge_buffer{3.0};
LateralAccelerationMap lane_change_lat_acc_map;
// parked vehicle
@@ -151,13 +151,17 @@ struct Parameters
bool allow_loose_check_for_cancel{true};
double collision_check_yaw_diff_threshold{3.1416};
utils::path_safety_checker::RSSparams rss_params{};
+ utils::path_safety_checker::RSSparams rss_params_for_parked{};
utils::path_safety_checker::RSSparams rss_params_for_abort{};
utils::path_safety_checker::RSSparams rss_params_for_stuck{};
// abort
CancelParameters cancel{};
+ // finish judge parameter
+ double lane_change_finish_judge_buffer{3.0};
double finish_judge_lateral_threshold{0.2};
+ double finish_judge_lateral_angle_deviation{autoware::universe_utils::deg2rad(3.0)};
// debug marker
bool publish_debug_marker{false};
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp
index 7bb6a06116a53..d566aceba413b 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp
@@ -314,6 +314,8 @@ bool is_ahead_of_ego(
bool is_before_terminal(
const CommonDataPtr & common_data_ptr, const PathWithLaneId & path,
const PredictedObject & object);
+
+double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, const Pose & pose);
} // namespace autoware::behavior_path_planner::utils::lane_change
namespace autoware::behavior_path_planner::utils::lane_change::debug
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml
index 74d11dbcb1e13..20fc894f7fc58 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/package.xml
@@ -13,6 +13,7 @@
Shumpei Wakabayashi
Tomohito Ando
Alqudah Mohammad
+ Maxime Clement
Apache License 2.0
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp
index 22c93f7d4bfd5..f3f371ec02a9b 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/manager.cpp
@@ -122,6 +122,23 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
p.rss_params.lateral_distance_max_threshold = getOrDeclareParameter(
*node, parameter("safety_check.execution.lateral_distance_max_threshold"));
+ p.rss_params_for_parked.longitudinal_distance_min_threshold = getOrDeclareParameter(
+ *node, parameter("safety_check.parked.longitudinal_distance_min_threshold"));
+ p.rss_params_for_parked.longitudinal_distance_min_threshold = getOrDeclareParameter(
+ *node, parameter("safety_check.parked.longitudinal_distance_min_threshold"));
+ p.rss_params_for_parked.longitudinal_velocity_delta_time = getOrDeclareParameter(
+ *node, parameter("safety_check.parked.longitudinal_velocity_delta_time"));
+ p.rss_params_for_parked.front_vehicle_deceleration = getOrDeclareParameter(
+ *node, parameter("safety_check.parked.expected_front_deceleration"));
+ p.rss_params_for_parked.rear_vehicle_deceleration = getOrDeclareParameter(
+ *node, parameter("safety_check.parked.expected_rear_deceleration"));
+ p.rss_params_for_parked.rear_vehicle_reaction_time = getOrDeclareParameter(
+ *node, parameter("safety_check.parked.rear_vehicle_reaction_time"));
+ p.rss_params_for_parked.rear_vehicle_safety_time_margin = getOrDeclareParameter(
+ *node, parameter("safety_check.parked.rear_vehicle_safety_time_margin"));
+ p.rss_params_for_parked.lateral_distance_max_threshold = getOrDeclareParameter(
+ *node, parameter("safety_check.parked.lateral_distance_max_threshold"));
+
p.rss_params_for_abort.longitudinal_distance_min_threshold = getOrDeclareParameter(
*node, parameter("safety_check.cancel.longitudinal_distance_min_threshold"));
p.rss_params_for_abort.longitudinal_velocity_delta_time = getOrDeclareParameter(
@@ -166,8 +183,6 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
getOrDeclareParameter(*node, parameter("minimum_lane_changing_velocity"));
p.minimum_lane_changing_velocity =
std::min(p.minimum_lane_changing_velocity, max_acc * p.lane_change_prepare_duration);
- p.lane_change_finish_judge_buffer =
- getOrDeclareParameter(*node, parameter("lane_change_finish_judge_buffer"));
if (p.backward_length_buffer_for_end_of_lane < 1.0) {
RCLCPP_WARN_STREAM(
@@ -224,8 +239,15 @@ void LaneChangeModuleManager::initParams(rclcpp::Node * node)
p.cancel.unsafe_hysteresis_threshold =
getOrDeclareParameter(*node, parameter("cancel.unsafe_hysteresis_threshold"));
+ // finish judge parameters
+ p.lane_change_finish_judge_buffer =
+ getOrDeclareParameter(*node, parameter("lane_change_finish_judge_buffer"));
p.finish_judge_lateral_threshold =
getOrDeclareParameter(*node, parameter("finish_judge_lateral_threshold"));
+ const auto finish_judge_lateral_angle_deviation =
+ getOrDeclareParameter(*node, parameter("finish_judge_lateral_angle_deviation"));
+ p.finish_judge_lateral_angle_deviation =
+ autoware::universe_utils::deg2rad(finish_judge_lateral_angle_deviation);
// debug marker
p.publish_debug_marker = getOrDeclareParameter(*node, parameter("publish_debug_marker"));
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp
index 97eab5a03fcaa..1bab71737da00 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp
@@ -14,6 +14,7 @@
#include "autoware/behavior_path_lane_change_module/scene.hpp"
+#include "autoware/behavior_path_lane_change_module/utils/calculation.hpp"
#include "autoware/behavior_path_lane_change_module/utils/utils.hpp"
#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp"
#include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
@@ -23,6 +24,7 @@
#include "autoware/behavior_path_planner_common/utils/utils.hpp"
#include
+#include
#include
#include
#include
@@ -44,6 +46,7 @@ using utils::lane_change::calcMinimumLaneChangeLength;
using utils::lane_change::create_lanes_polygon;
using utils::path_safety_checker::isPolygonOverlapLanelet;
using utils::traffic_light::getDistanceToNextTrafficLight;
+namespace calculation = utils::lane_change::calculation;
NormalLaneChange::NormalLaneChange(
const std::shared_ptr & parameters, LaneChangeModuleType type,
@@ -391,16 +394,9 @@ void NormalLaneChange::insertStopPoint(
const auto target_objects = filterObjects();
double stopping_distance = distance_to_terminal - lane_change_buffer - stop_point_buffer;
- const auto is_valid_start_point = std::invoke([&]() -> bool {
- auto lc_start_point = lanelet::utils::conversion::toLaneletPoint(
- status_.lane_change_path.info.lane_changing_start.position);
- const auto & target_neighbor_preferred_lane_poly_2d =
- common_data_ptr_->lanes_polygon_ptr->target_neighbor;
- return boost::geometry::covered_by(
- lanelet::traits::to2D(lc_start_point), target_neighbor_preferred_lane_poly_2d);
- });
+ const auto & lc_start_point = status_.lane_change_path.info.lane_changing_start;
- if (!is_valid_start_point) {
+ if (!is_valid_start_point(common_data_ptr_, lc_start_point)) {
const auto stop_point = utils::insertStopPoint(stopping_distance, path);
setStopPose(stop_point.point.pose);
@@ -689,21 +685,33 @@ bool NormalLaneChange::hasFinishedLaneChange() const
const auto & lane_change_end = status_.lane_change_path.info.shift_line.end;
const auto & target_lanes = get_target_lanes();
const double dist_to_lane_change_end =
- utils::getSignedDistance(current_pose, lane_change_end, get_target_lanes());
- double finish_judge_buffer = lane_change_parameters_->lane_change_finish_judge_buffer;
+ utils::getSignedDistance(current_pose, lane_change_end, target_lanes);
- // If ego velocity is low, relax finish judge buffer
- const double ego_velocity = getEgoVelocity();
- if (std::abs(ego_velocity) < 1.0) {
- finish_judge_buffer = 0.0;
- }
+ const auto finish_judge_buffer = std::invoke([&]() {
+ const double ego_velocity = getEgoVelocity();
+ // If ego velocity is low, relax finish judge buffer
+ if (std::abs(ego_velocity) < 1.0) {
+ return 0.0;
+ }
+ return lane_change_parameters_->lane_change_finish_judge_buffer;
+ });
- const auto reach_lane_change_end = dist_to_lane_change_end + finish_judge_buffer < 0.0;
+ const auto has_passed_end_pose = dist_to_lane_change_end + finish_judge_buffer < 0.0;
lane_change_debug_.distance_to_lane_change_finished =
dist_to_lane_change_end + finish_judge_buffer;
- if (!reach_lane_change_end) {
+ if (has_passed_end_pose) {
+ const auto & lanes_polygon = common_data_ptr_->lanes_polygon_ptr->target;
+ return !boost::geometry::disjoint(
+ lanes_polygon.value(),
+ lanelet::utils::to2D(lanelet::utils::conversion::toLaneletPoint(current_pose.position)));
+ }
+
+ const auto yaw_deviation_to_centerline =
+ utils::lane_change::calc_angle_to_lanelet_segment(target_lanes, current_pose);
+
+ if (yaw_deviation_to_centerline > lane_change_parameters_->finish_judge_lateral_angle_deviation) {
return false;
}
@@ -1220,8 +1228,6 @@ PathWithLaneId NormalLaneChange::getTargetSegment(
std::min(dist_from_start, dist_from_end), s_start + std::numeric_limits::epsilon());
});
- RCLCPP_DEBUG(logger_, "in %s start: %f, end: %f", __func__, s_start, s_end);
-
PathWithLaneId target_segment = route_handler.getCenterLinePath(target_lanes, s_start, s_end);
for (auto & point : target_segment.points) {
point.point.longitudinal_velocity_mps =
@@ -1357,7 +1363,7 @@ bool NormalLaneChange::getLaneChangePaths(
route_handler.getLateralIntervalsToPreferredLane(target_lanes.back()));
const auto dist_to_end_of_current_lanes =
- utils::getDistanceToEndOfLane(getEgoPose(), current_lanes);
+ calculation::calc_ego_dist_to_terminal_end(common_data_ptr_);
const auto target_lane_length = lanelet::utils::getLaneletLength2d(target_lanes);
@@ -1385,12 +1391,6 @@ bool NormalLaneChange::getLaneChangePaths(
for (const auto & prepare_duration : prepare_durations) {
for (const auto & sampled_longitudinal_acc : longitudinal_acc_sampling_values) {
- const auto debug_print = [&](const auto & s) {
- RCLCPP_DEBUG_STREAM(
- logger_, " - " << s << " : prep_time = " << prepare_duration
- << ", lon_acc = " << sampled_longitudinal_acc);
- };
-
// get path on original lanes
const auto prepare_velocity = std::clamp(
current_velocity + sampled_longitudinal_acc * prepare_duration,
@@ -1404,13 +1404,35 @@ bool NormalLaneChange::getLaneChangePaths(
const auto prepare_length = utils::lane_change::calcPhaseLength(
current_velocity, getCommonParam().max_vel, longitudinal_acc_on_prepare, prepare_duration);
+ const auto ego_dist_to_terminal_start = dist_to_end_of_current_lanes - lane_change_buffer;
+ if (prepare_length > ego_dist_to_terminal_start) {
+ RCLCPP_DEBUG(
+ logger_,
+ "Reject: Prepare length exceed distance to terminal start. prep_len: %.5f, ego dist to "
+ "terminal start: %.5f",
+ prepare_length, ego_dist_to_terminal_start);
+ continue;
+ }
+
auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length);
+ const auto debug_print = [&](const auto & s) {
+ RCLCPP_DEBUG(
+ logger_, "%s | prep_time: %.5f | lon_acc sampled: %.5f, actual: %.5f | prep_len: %.5f", s,
+ prepare_duration, sampled_longitudinal_acc, longitudinal_acc_on_prepare, prepare_length);
+ };
+
if (prepare_segment.points.empty()) {
debug_print("prepare segment is empty...? Unexpected.");
continue;
}
+ if (!is_valid_start_point(common_data_ptr_, prepare_segment.points.back().point.pose)) {
+ debug_print(
+ "Reject: lane changing start point is not within the preferred lanes or its neighbors");
+ continue;
+ }
+
// lane changing start getEgoPose() is at the end of prepare segment
const auto & lane_changing_start_pose = prepare_segment.points.back().point.pose;
const auto target_length_from_lane_change_start_pose = utils::getArcLengthToTargetLanelet(
@@ -1441,13 +1463,8 @@ bool NormalLaneChange::getLaneChangePaths(
}
RCLCPP_DEBUG(logger_, " - sampling num for lat_acc: %lu", sample_lat_acc.size());
+ debug_print("Prepare path satisfy constraints");
for (const auto & lateral_acc : sample_lat_acc) {
- const auto debug_print_lat = [&](const auto & s) {
- RCLCPP_DEBUG_STREAM(
- logger_, " - " << s << " : prep_time = " << prepare_duration << ", lon_acc = "
- << sampled_longitudinal_acc << ", lat_acc = " << lateral_acc);
- };
-
const auto lane_changing_time = PathShifter::calcShiftTimeFromJerk(
shift_length, lane_change_parameters_->lane_changing_lateral_jerk, lateral_acc);
const double longitudinal_acc_on_lane_changing =
@@ -1463,6 +1480,14 @@ bool NormalLaneChange::getLaneChangePaths(
utils::lane_change::setPrepareVelocity(
prepare_segment, current_velocity, terminal_lane_changing_velocity);
+ const auto debug_print_lat = [&](const auto & s) {
+ RCLCPP_DEBUG(
+ logger_,
+ " - %s | lc_time: %.5f | lon_acc sampled: %.5f, actual: %.5f | lc_len: %.5f", s,
+ lane_changing_time, sampled_longitudinal_acc, longitudinal_acc_on_lane_changing,
+ lane_changing_length);
+ };
+
if (lane_changing_length + prepare_length > dist_to_end_of_current_lanes) {
debug_print_lat("Reject: length of lane changing path is longer than length to goal!!");
continue;
@@ -1497,16 +1522,6 @@ bool NormalLaneChange::getLaneChangePaths(
continue;
}
- const lanelet::BasicPoint2d lc_start_point(
- prepare_segment.points.back().point.pose.position.x,
- prepare_segment.points.back().point.pose.position.y);
-
- const auto target_lane_poly_2d = common_data_ptr_->lanes_polygon_ptr->target.value();
-
- const auto is_valid_start_point =
- boost::geometry::covered_by(lc_start_point, target_neighbor_preferred_lane_poly_2d) ||
- boost::geometry::covered_by(lc_start_point, target_lane_poly_2d);
-
LaneChangeInfo lane_change_info;
lane_change_info.longitudinal_acceleration =
LaneChangePhaseInfo{longitudinal_acc_on_prepare, longitudinal_acc_on_lane_changing};
@@ -1519,13 +1534,6 @@ bool NormalLaneChange::getLaneChangePaths(
lane_change_info.lateral_acceleration = lateral_acc;
lane_change_info.terminal_lane_changing_velocity = terminal_lane_changing_velocity;
- if (!is_valid_start_point) {
- debug_print_lat(
- "Reject: lane changing points are not inside of the target preferred lanes or its "
- "neighbors");
- continue;
- }
-
const auto resample_interval = utils::lane_change::calcLaneChangeResampleInterval(
lane_changing_length, initial_lane_changing_velocity);
const auto target_lane_reference_path = utils::lane_change::getReferencePathFromTargetLane(
@@ -2069,9 +2077,14 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj(
obj, lane_change_parameters_->use_all_predicted_path);
auto is_safe = true;
+ const auto selected_rss_param =
+ (obj.initial_twist.twist.linear.x <=
+ lane_change_parameters_->prepare_segment_ignore_object_velocity_thresh)
+ ? lane_change_parameters_->rss_params_for_parked
+ : rss_params;
for (const auto & obj_path : obj_predicted_paths) {
const auto collided_polygons = utils::path_safety_checker::getCollidedPolygons(
- path, ego_predicted_path, obj, obj_path, common_parameters, rss_params, 1.0,
+ path, ego_predicted_path, obj, obj_path, common_parameters, selected_rss_param, 1.0,
get_max_velocity_for_safety_check(), collision_check_yaw_diff_threshold,
current_debug_data.second);
@@ -2209,6 +2222,18 @@ bool NormalLaneChange::isVehicleStuck(const lanelet::ConstLanelets & current_lan
return is_vehicle_stuck;
}
+bool NormalLaneChange::is_valid_start_point(
+ const lane_change::CommonDataPtr & common_data_ptr, const Pose & pose) const
+{
+ const lanelet::BasicPoint2d lc_start_point(pose.position.x, pose.position.y);
+
+ const auto & target_neighbor_poly = common_data_ptr->lanes_polygon_ptr->target_neighbor;
+ const auto & target_lane_poly = common_data_ptr_->lanes_polygon_ptr->target.value();
+
+ return boost::geometry::covered_by(lc_start_point, target_neighbor_poly) ||
+ boost::geometry::covered_by(lc_start_point, target_lane_poly);
+}
+
void NormalLaneChange::setStopPose(const Pose & stop_pose)
{
lane_change_stop_pose_ = stop_pose;
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp
new file mode 100644
index 0000000000000..521c30d406e7a
--- /dev/null
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp
@@ -0,0 +1,45 @@
+// Copyright 2024 TIER IV, Inc.
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include
+#include
+
+namespace autoware::behavior_path_planner::utils::lane_change::calculation
+{
+double calc_ego_dist_to_terminal_end(const CommonDataPtr & common_data_ptr)
+{
+ const auto & lanes_ptr = common_data_ptr->lanes_ptr;
+ const auto & current_lanes = lanes_ptr->current;
+ const auto & current_pose = common_data_ptr->get_ego_pose();
+
+ return calc_dist_from_pose_to_terminal_end(common_data_ptr, current_lanes, current_pose);
+}
+
+double calc_dist_from_pose_to_terminal_end(
+ const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & lanes,
+ const Pose & src_pose)
+{
+ if (lanes.empty()) {
+ return 0.0;
+ }
+
+ const auto & lanes_ptr = common_data_ptr->lanes_ptr;
+ const auto & goal_pose = common_data_ptr->route_handler_ptr->getGoalPose();
+
+ if (lanes_ptr->current_lane_in_goal_section) {
+ return utils::getSignedDistance(src_pose, goal_pose, lanes);
+ }
+ return utils::getDistanceToEndOfLane(src_pose, lanes);
+}
+} // namespace autoware::behavior_path_planner::utils::lane_change::calculation
diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp
index 176a7ece0084e..7e93365a59e7b 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp
+++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp
@@ -1343,6 +1343,17 @@ bool is_before_terminal(
}
return current_max_dist >= 0.0;
}
+
+double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, const Pose & pose)
+{
+ lanelet::ConstLanelet closest_lanelet;
+
+ if (!lanelet::utils::query::getClosestLanelet(lanelets, pose, &closest_lanelet)) {
+ return autoware::universe_utils::deg2rad(180);
+ }
+ const auto closest_pose = lanelet::utils::getClosestCenterPose(closest_lanelet, pose.position);
+ return std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, pose));
+}
} // namespace autoware::behavior_path_planner::utils::lane_change
namespace autoware::behavior_path_planner::utils::lane_change::debug
diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml
index ef6cb82d1412a..f94657c1418e4 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml
+++ b/planning/behavior_path_planner/autoware_behavior_path_planner/config/scene_module_manager.param.yaml
@@ -3,80 +3,80 @@
# NOTE: The smaller the priority number is, the higher the module priority is.
/**:
ros__parameters:
+ # NOTE: modules which are not set true in the preset is ignored in the slot configuration
+ slots:
+ # NOTE: array of array is not supported
+ - slot1
+ - slot2
+ - slot3
+ - slot4
+ slot1:
+ - "start_planner"
+ slot2:
+ - "side_shift"
+ - "avoidance_by_lane_change"
+ - "static_obstacle_avoidance"
+ - "lane_change_left"
+ - "lane_change_right"
+ - "external_request_lane_change_left"
+ - "external_request_lane_change_right"
+ slot3:
+ - "goal_planner"
+ slot4:
+ - "dynamic_obstacle_avoidance"
+
external_request_lane_change_left:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 6
external_request_lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 6
lane_change_left:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 5
lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 5
start_planner:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
- keep_last: false
- priority: 0
side_shift:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
- keep_last: false
- priority: 2
goal_planner:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
- keep_last: true
- priority: 1
static_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
- keep_last: false
- priority: 4
avoidance_by_lane_change:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
- keep_last: false
- priority: 3
dynamic_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
- keep_last: false
- priority: 7
sampling_planner:
enable_module: true
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
- keep_last: true
- priority: 16
diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md b/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md
index 09627d2d5d91e..68d81f4d257c1 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md
+++ b/planning/behavior_path_planner/autoware_behavior_path_planner/docs/behavior_path_planner_manager_design.md
@@ -46,6 +46,31 @@ Additionally, the manager generates root reference path, and if any other module
![manager_overview](../image/manager/manager_overview.svg)
+### Slot
+
+The manager owns several containers of sub-managers, namely _slots_, that holds/runs several sub-managers and send the output to the next slot. Given the initial reference path, each slot processes the input path and the output path is processed by the next slot. The final slot output is utilized as the output of the manager. The slot passes following information
+
+```cpp
+struct SlotOutput
+{
+ BehaviorModuleOutput valid_output;
+
+ // if candidate module is running, valid_output contains the planning by candidate module. In
+ // that case, downstream slots will just run aproved modules and do not try to launch new
+ // modules
+ bool is_upstream_candidate_exclusive{false};
+
+ // if this slot failed, downstream slots need to refresh approved/candidate modules and just
+ // forward valid_output of this slot output
+ bool is_upstream_failed_approved{false};
+
+ // if the approved module in this slot returned to isWaitingApproval, downstream slots need to
+ // refresh candidate once
+ bool is_upstream_waiting_approved{false};
+};
+
+```
+
### Sub-managers
The sub-manager's main task is
@@ -136,13 +161,13 @@ There are 6 steps in one process:
At first, the manager set latest planner data, and run all approved modules and get output path. At this time, the manager checks module status and removes expired modules from approved modules stack.
-![process_step1](../image/manager/process_step1.svg)
+![process_step1](../image/manager/process_step1.drawio.svg)
### Step2
Input approved modules output and necessary data to all registered modules, and the modules judge the necessity of path modification based on it. The manager checks which module makes execution request.
-![process_step2](../image/manager/process_step2.svg)
+![process_step2](../image/manager/process_step2.drawio.svg)
### Step3
@@ -152,19 +177,19 @@ Check request module existence.
The manager decides which module to execute as candidate modules from the modules that requested to execute path modification.
-![process_step4](../image/manager/process_step4.svg)
+![process_step4](../image/manager/process_step4.drawio.svg)
### Step5
Decides the priority order of execution among candidate modules. And, run all candidate modules. Each modules outputs reference path and RTC cooperate status.
-![process_step5](../image/manager/process_step5.svg)
+![process_step5](../image/manager/process_step5.drawio.svg)
### Step6
Move approved module to approved modules stack from candidate modules stack.
-![process_step6](../image/manager/process_step6.svg)
+![process_step6](../image/manager/process_step6.drawio.svg)
---
@@ -377,20 +402,20 @@ If a module that doesn't support simultaneous execution exists in approved modul
For example, if approved module's setting of `enable_simultaneous_execution_as_approved_module` is **ENABLE**, then only modules whose the setting is **ENABLE** proceed to the next step.
-![request_step2](../image/manager/request_step2.svg)
+![request_step2](../image/manager/request_step2.drawio.svg)
Other examples:
-| Process | Description |
-| :------------------------------------------------------- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-| ![request_step2-2](../image/manager/request_step2-2.svg) | If approved modules stack is empty, then all request modules proceed to the next step, regardless of the setting of `enable_simultaneous_execution_as_approved_module`. |
-| ![request_step2-3](../image/manager/request_step2-3.svg) | If approved module's setting of `enable_simultaneous_execution_as_approved_module` is **DISABLE**, then all request modules are discarded. |
+| Process | Description |
+| :-------------------------------------------------------------- | :---------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| ![request_step2-2](../image/manager/request_step2-2.drawio.svg) | If approved modules stack is empty, then all request modules proceed to the next step, regardless of the setting of `enable_simultaneous_execution_as_approved_module`. |
+| ![request_step2-3](../image/manager/request_step2-3.drawio.svg) | If approved module's setting of `enable_simultaneous_execution_as_approved_module` is **DISABLE**, then all request modules are discarded. |
### Step3
Sort `request_modules` by priority.
-![request_step3](../image/manager/request_step3.svg)
+![request_step3](../image/manager/request_step3.drawio.svg)
### Step4
@@ -444,26 +469,26 @@ Executable or not:
For example, if the highest priority module's setting of `enable_simultaneous_execution_as_candidate_module` is **DISABLE**, then all modules after the second priority are discarded.
-![request_step4](../image/manager/request_step4.svg)
+![request_step4](../image/manager/request_step4.drawio.svg)
Other examples:
-| Process | Description |
-| :------------------------------------------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-| ![request_step4-2](../image/manager/request_step4-2.svg) | If a module with a higher priority exists, lower priority modules whose setting of `enable_simultaneous_execution_as_candidate_module` is **DISABLE** are discarded. |
-| ![request_step4-3](../image/manager/request_step4-3.svg) | If all modules' setting of `enable_simultaneous_execution_as_candidate_module` is **ENABLE**, then all modules proceed to the next step. |
+| Process | Description |
+| :-------------------------------------------------------------- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| ![request_step4-2](../image/manager/request_step4-2.drawio.svg) | If a module with a higher priority exists, lower priority modules whose setting of `enable_simultaneous_execution_as_candidate_module` is **DISABLE** are discarded. |
+| ![request_step4-3](../image/manager/request_step4-3.drawio.svg) | If all modules' setting of `enable_simultaneous_execution_as_candidate_module` is **ENABLE**, then all modules proceed to the next step. |
### Step5
Run all candidate modules.
-![request_step5](../image/manager/request_step5.svg)
+![request_step5](../image/manager/request_step5.drawio.svg)
## How to decide which module's output to use?
Sometimes, multiple candidate modules are running simultaneously.
-![multiple_candidates](../image/manager/multiple_candidates.svg)
+![multiple_candidates](../image/manager/multiple_candidates.drawio.svg)
In this case, the manager selects a candidate modules which output path is used as `behavior_path_planner` output by approval condition in the following rules.
@@ -482,11 +507,11 @@ In this case, the manager selects a candidate modules which output path is used
The smaller the number is, the higher the priority is.
- ![module_select](../image/manager/module_select.svg){width=1000}
+ ![module_select](../image/manager/module_select.drawio.svg){width=1000}
module priority
-![output_module](../image/manager/output_module.svg)
+![output_module](../image/manager/output_module.drawio.svg)
Additionally, the manager moves the highest priority module to approved modules stack if it is already approved.
@@ -502,7 +527,9 @@ This is because module C is planning output path with the output of module B as
As a result, the module A's output is used as approved modules stack.
-![waiting_approve](../image/manager/waiting_approve.svg)
+![waiting_approve](../image/manager/waiting_approve.drawio.svg)
+
+If this case happened in the slot, `is_upstream_waiting_approved` is set to true.
### Failure modules
@@ -510,24 +537,45 @@ The failure modules return the status `ModuleStatus::FAILURE`. The manager remov
As a result, the module A's output is used as approved modules stack.
-![failure_modules](../image/manager/failure_modules.svg)
+![failure_modules](../image/manager/failure_modules.drawio.svg)
+
+If this case happened in the slot, `is_upstream_failed_approved` is set to true.
### Succeeded modules
The succeeded modules return the status `ModuleStatus::SUCCESS`. The manager removes those modules based on **Last In First Out** policy. In other words, if a module added later to approved modules stack is still running (is in `ModuleStatus::RUNNING`), the manager doesn't remove the succeeded module. The reason for this is the same as in removal for waiting approval modules, and is to prevent sudden changes of the running module's output.
-![success_modules_remove](../image/manager/success_modules_remove.svg)
+![success_modules_remove](../image/manager/success_modules_remove.drawio.svg)
-![success_modules_skip](../image/manager/success_modules_skip.svg)
+![success_modules_skip](../image/manager/success_modules_skip.drawio.svg)
As an exception, if **Lane Change** module returns status `ModuleStatus::SUCCESS`, the manager doesn't remove any modules until all modules is in status `ModuleStatus::SUCCESS`. This is because when the manager removes the **Lane Change** (normal LC, external LC, avoidance by LC) module as succeeded module, the manager updates the information of the lane Ego is currently driving in, so root reference path (= module A's input path) changes significantly at that moment.
-![lane_change_remove](../image/manager/lane_change_remove.svg)
+![lane_change_remove](../image/manager/lane_change_remove.drawio.svg)
-![lane_change_skip](../image/manager/lane_change_skip.svg)
+![lane_change_skip](../image/manager/lane_change_skip.drawio.svg)
When the manager removes succeeded modules, the last added module's output is used as approved modules stack.
+## Slot output propagation
+
+As the initial solution, following _SlotOutput_ is passed to the first slot.
+
+```cpp
+ SlotOutput result_output = SlotOutput{
+ getReferencePath(data),
+ false,
+ false,
+ false,
+ };
+```
+
+If a slot turned out to be `is_upstream_failed_approved`, then all the subsequent slots are refreshed and have all of their approved_modules and candidate_modules cleared. The valid_output is just transferred to the end without any modification.
+
+If a slot turned out to be `is_upstream_waiting_approved`, then all the subsequent slots clear their candidate_modules once and apply their approved_modules to obtain the slot output.
+
+If a slot turned out to be `is_upstream_candidate_exclusive`, it means that a not `simultaneously_executable_as_candidate` module is running in that slot. Then all the subsequent modules just apply their approved_modules without trying to launch new candidate_modules.
+
## Reference path generation
The reference path is generated from the centerline of the **lanelet sequence** obtained from the **current route lanelet**, and it is not only used as an input to the first added module of approved modules stack, but also used as the output of `behavior_path_planner` if none of the modules are running.
diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/image/manager/failure_modules.svg b/planning/behavior_path_planner/autoware_behavior_path_planner/image/manager/failure_modules.drawio.svg
similarity index 73%
rename from planning/behavior_path_planner/autoware_behavior_path_planner/image/manager/failure_modules.svg
rename to planning/behavior_path_planner/autoware_behavior_path_planner/image/manager/failure_modules.drawio.svg
index 78653e8f9170b..afe1842e46595 100644
--- a/planning/behavior_path_planner/autoware_behavior_path_planner/image/manager/failure_modules.svg
+++ b/planning/behavior_path_planner/autoware_behavior_path_planner/image/manager/failure_modules.drawio.svg
@@ -1,25 +1,26 @@
+