diff --git a/build_depends.repos b/build_depends.repos index 110eb1045d777..d77a076a5ec5d 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -41,8 +41,3 @@ repositories: type: git url: https://github.com/MORAI-Autonomous/MORAI-ROS2_morai_msgs.git version: main - #vehicle - vehicle/sample_vehicle_launch: - type: git - url: https://github.com/autowarefoundation/sample_vehicle_launch.git - version: main diff --git a/common/global_parameter_loader/CMakeLists.txt b/common/global_parameter_loader/CMakeLists.txt index eaca44c515452..e67ae1a5c06fc 100644 --- a/common/global_parameter_loader/CMakeLists.txt +++ b/common/global_parameter_loader/CMakeLists.txt @@ -4,11 +4,6 @@ project(global_parameter_loader) find_package(autoware_cmake REQUIRED) autoware_package() -if(BUILD_TESTING) - file(GLOB_RECURSE test_files test/*.cpp) - ament_add_ros_isolated_gtest(test_global_params_launch ${test_files}) -endif() - ament_auto_package( INSTALL_TO_SHARE launch diff --git a/common/global_parameter_loader/package.xml b/common/global_parameter_loader/package.xml index 78d08e4038250..4c2568b9aec98 100644 --- a/common/global_parameter_loader/package.xml +++ b/common/global_parameter_loader/package.xml @@ -10,10 +10,8 @@ ament_cmake_auto autoware_cmake - sample_vehicle_description - vehicle_info_util + vehicle_info_util - ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/common/global_parameter_loader/test/test_global_params_launch.cpp b/common/global_parameter_loader/test/test_global_params_launch.cpp deleted file mode 100644 index 2b33a695253ff..0000000000000 --- a/common/global_parameter_loader/test/test_global_params_launch.cpp +++ /dev/null @@ -1,44 +0,0 @@ -// Copyright 2023 The 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 - -#include -#include -#include - -TEST(TestLaunchFile, test_launch_file) -{ - // Define the path of Python launch file - std::string global_params_launch_path = "global_params.launch.py"; - - // Define the parameters you want to pass to the launch file - std::string use_sim_time_param = "false"; - std::string vehicle_model_param = "sample_vehicle"; - // Construct the command to run the Python launch script with parameters - std::string command = "ros2 launch global_parameter_loader " + global_params_launch_path + - " use_sim_time:=" + use_sim_time_param + - " vehicle_model:=" + vehicle_model_param; - - // Use the system() function to execute the command - int result = std::system(command.c_str()); - // Check the result of running the launch file - EXPECT_EQ(result, 0); -} - -int main(int argc, char * argv[]) -{ - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml index f54d991a9d852..b033711da6dac 100644 --- a/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml +++ b/common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml @@ -51,10 +51,14 @@ Planning: behavior_path_avoidance_by_lane_change: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: lane_change.AVOIDANCE_BY_LANE_CHANGE + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: lane_change.utils behavior_path_lane_change: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner logger_name: lane_change.NORMAL + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: lane_change.utils behavior_velocity_planner: - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner @@ -78,6 +82,10 @@ Planning: - node_name: /planning/scenario_planning/motion_velocity_smoother logger_name: tier4_autoware_utils + route_handler: + - node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner + logger_name: route_handler + # ============================================================ # control # ============================================================ diff --git a/control/autonomous_emergency_braking/README.md b/control/autonomous_emergency_braking/README.md index 28b7636ba82ac..a4e737ca545be 100644 --- a/control/autonomous_emergency_braking/README.md +++ b/control/autonomous_emergency_braking/README.md @@ -86,20 +86,28 @@ where $v$ and $\omega$ are current longitudinal velocity and angular velocity re ### 3. Get target obstacles from the input point cloud -After generating the ego predicted path, we select target obstacles from the input point cloud. This obstacle filtering has two major steps, which are rough filtering and rigorous filtering. +After generating the ego predicted path, we select target obstacles from the input point cloud. This obstacle filtering has three major steps, which are rough filtering, noise filtering with clustering and rigorous filtering. #### Rough filtering -In rough filtering step, we select target obstacle with simple filter. Create a search area up to a certain distance (default 5[m]) away from the predicted path of the ego vehicle and ignore the point cloud (obstacles) that are not within it. The image of the rough filtering is illustrated below. +In rough filtering step, we select target obstacle with simple filter. Create a search area up to a certain distance (default is half of the ego vehicle width plus the `path_footprint_extra_margin` parameter) away from the predicted path of the ego vehicle and ignore the point cloud that are not within it. The image of the rough filtering is illustrated below. ![rough_filtering](./image/obstacle_filtering_1.drawio.svg) +#### Noise filtering with clustering and convex hulls + +To prevent the AEB from considering noisy points, euclidean clustering is performed on the filtered point cloud. The points in the point cloud that are not close enough to other points to form a cluster are discarded. The parameters `cluster_tolerance`, `minimum_cluster_size` and `maximum_cluster_size` can be used to tune the clustering and the size of objects to be ignored, for more information about the clustering method used by the AEB module, please check the official documentation on euclidean clustering of the PCL library: . + +Furthermore, a 2D convex hull is created around each detected cluster, the vertices of each hull represent the most extreme/outside points of the cluster. These vertices are then checked in the next step. + #### Rigorous filtering -After rough filtering, it performs a geometric collision check to determine whether the filtered obstacles actually have possibility to collide with the ego vehicle. In this check, the ego vehicle is represented as a rectangle, and the point cloud obstacles are represented as points. +After Noise filtering, it performs a geometric collision check to determine whether the filtered obstacles/hull vertices actually have possibility to collide with the ego vehicle. In this check, the ego vehicle is represented as a rectangle, and the point cloud obstacles are represented as points. Only the vertices with a possibility of collision are kept. ![rigorous_filtering](./image/obstacle_filtering_2.drawio.svg) +Finally, the vertex that is closest to the ego vehicle is chosen as the candidate for collision checking: Since rss distance is used to judge if a collision will happen or not, if the closest vertex to the ego is deemed to be safe, the rest of the vertices (and the points in the clusters) will also be safe. + ### 4. Collision check with target obstacles In the fourth step, it checks the collision with filtered obstacles using RSS distance. RSS is formulated as: diff --git a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml index 82d5a4f12e002..bb429662dabfb 100644 --- a/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml +++ b/control/autonomous_emergency_braking/config/autonomous_emergency_braking.param.yaml @@ -3,6 +3,7 @@ publish_debug_pointcloud: false use_predicted_trajectory: true use_imu_path: true + path_footprint_extra_margin: 1.0 detection_range_min_height: 0.0 detection_range_max_height_margin: 0.0 voxel_grid_x: 0.05 @@ -14,6 +15,9 @@ t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 + cluster_tolerance: 0.1 #[m] + minimum_cluster_size: 10 + maximum_cluster_size: 10000 imu_prediction_time_horizon: 1.5 imu_prediction_time_interval: 0.1 mpc_prediction_time_horizon: 1.5 diff --git a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp index 50affd3fb1328..53a913192c1e6 100644 --- a/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp +++ b/control/autonomous_emergency_braking/include/autonomous_emergency_braking/node.hpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include @@ -64,7 +65,6 @@ using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; using Path = std::vector; using Vector3 = geometry_msgs::msg::Vector3; - struct ObjectData { rclcpp::Time stamp; @@ -138,15 +138,19 @@ class AEB : public rclcpp::Node // main function void onCheckCollision(DiagnosticStatusWrapper & stat); bool checkCollision(MarkerArray & debug_markers); - bool hasCollision( - const double current_v, const Path & ego_path, const std::vector & objects); + bool hasCollision(const double current_v, const ObjectData & closest_object); + + Path generateEgoPath(const double curr_v, const double curr_w); + std::optional generateEgoPath(const Trajectory & predicted_traj); + std::vector generatePathFootprint(const Path & path, const double extra_width_margin); - Path generateEgoPath(const double curr_v, const double curr_w, std::vector & polygons); - std::optional generateEgoPath( - const Trajectory & predicted_traj, std::vector & polygons); - void createObjectData( + void createObjectDataUsingPointCloudClusters( const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, - std::vector & objects); + std::vector & objects, + const pcl::PointCloud::Ptr obstacle_points_ptr); + + void cropPointCloudWithEgoFootprintPath( + const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects); void addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, @@ -175,6 +179,7 @@ class AEB : public rclcpp::Node bool publish_debug_pointcloud_; bool use_predicted_trajectory_; bool use_imu_path_; + double path_footprint_extra_margin_; double detection_range_min_height_; double detection_range_max_height_margin_; double voxel_grid_x_; @@ -186,6 +191,9 @@ class AEB : public rclcpp::Node double t_response_; double a_ego_min_; double a_obj_min_; + double cluster_tolerance_; + int minimum_cluster_size_; + int maximum_cluster_size_; double imu_prediction_time_horizon_; double imu_prediction_time_interval_; double mpc_prediction_time_horizon_; diff --git a/control/autonomous_emergency_braking/src/node.cpp b/control/autonomous_emergency_braking/src/node.cpp index 3890d3fd2d369..e1ab383aa7d1c 100644 --- a/control/autonomous_emergency_braking/src/node.cpp +++ b/control/autonomous_emergency_braking/src/node.cpp @@ -15,14 +15,25 @@ #include "autonomous_emergency_braking/node.hpp" #include +#include +#include #include #include #include +#include +#include #include +#include +#include +#include #include #include +#include +#include +#include +#include #include #ifdef ROS_DISTRO_GALACTIC @@ -34,8 +45,6 @@ #include #endif -#include -#include namespace autoware::motion::control::autonomous_emergency_braking { using diagnostic_msgs::msg::DiagnosticStatus; @@ -129,6 +138,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) publish_debug_pointcloud_ = declare_parameter("publish_debug_pointcloud"); use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); use_imu_path_ = declare_parameter("use_imu_path"); + 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_ = declare_parameter("detection_range_max_height_margin"); @@ -141,6 +151,11 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) t_response_ = declare_parameter("t_response"); a_ego_min_ = declare_parameter("a_ego_min"); a_obj_min_ = declare_parameter("a_obj_min"); + + cluster_tolerance_ = declare_parameter("cluster_tolerance"); + minimum_cluster_size_ = declare_parameter("minimum_cluster_size"); + maximum_cluster_size_ = declare_parameter("maximum_cluster_size"); + imu_prediction_time_horizon_ = declare_parameter("imu_prediction_time_horizon"); imu_prediction_time_interval_ = declare_parameter("imu_prediction_time_interval"); mpc_prediction_time_horizon_ = declare_parameter("mpc_prediction_time_horizon"); @@ -152,7 +167,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) // start time const double aeb_hz = declare_parameter("aeb_hz"); const auto period_ns = rclcpp::Rate(aeb_hz).period(); - timer_ = rclcpp::create_timer(this, get_clock(), period_ns, std::bind(&AEB::onTimer, this)); + timer_ = rclcpp::create_timer(this, this->get_clock(), period_ns, std::bind(&AEB::onTimer, this)); } void AEB::onTimer() @@ -242,11 +257,9 @@ void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg) filter.filter(*no_height_filtered_pointcloud_ptr); obstacle_ros_pointcloud_ptr_ = std::make_shared(); + pcl::toROSMsg(*no_height_filtered_pointcloud_ptr, *obstacle_ros_pointcloud_ptr_); obstacle_ros_pointcloud_ptr_->header = input_msg->header; - if (publish_debug_pointcloud_) { - pub_obstacle_pointcloud_->publish(*obstacle_ros_pointcloud_ptr_); - } } bool AEB::isDataReady() @@ -304,6 +317,8 @@ void AEB::onCheckCollision(DiagnosticStatusWrapper & stat) bool AEB::checkCollision(MarkerArray & debug_markers) { + using colorTuple = std::tuple; + // step1. check data if (!isDataReady()) { return false; @@ -320,86 +335,101 @@ bool AEB::checkCollision(MarkerArray & debug_markers) return false; } - // step3. create ego path based on sensor data - bool has_collision_ego = false; - if (use_imu_path_) { - std::vector ego_polys; + auto check_collision = [&]( + const auto & path, const colorTuple & debug_colors, + const std::string & debug_ns, const rclcpp::Time & current_time, + pcl::PointCloud::Ptr filtered_objects) { + // Crop out Pointcloud using an extra wide ego path + const auto expanded_ego_polys = + generatePathFootprint(path, expand_width_ + path_footprint_extra_margin_); + cropPointCloudWithEgoFootprintPath(expanded_ego_polys, filtered_objects); + + // Check which points of the cropped point cloud are on the ego path, and get the closest one + std::vector objects_from_point_clusters; + const auto ego_polys = generatePathFootprint(path, expand_width_); + createObjectDataUsingPointCloudClusters( + path, ego_polys, current_time, objects_from_point_clusters, filtered_objects); + + // Add debug markers + const auto [color_r, color_g, color_b, color_a] = debug_colors; + addMarker( + current_time, path, ego_polys, objects_from_point_clusters, color_r, color_g, color_b, + color_a, debug_ns, debug_markers); + + // Get only the closest object + const auto closest_object_point = std::min_element( + objects_from_point_clusters.begin(), objects_from_point_clusters.end(), + [](const auto & o1, const auto & o2) { + return o1.distance_to_object < o2.distance_to_object; + }); + + // check for empty vector + return (closest_object_point != objects_from_point_clusters.end()) + ? hasCollision(current_v, *closest_object_point) + : false; + }; + + // step3. make function to check collision with ego path created with sensor data + const auto has_collision_ego = [&](pcl::PointCloud::Ptr filtered_objects) -> bool { + if (!use_imu_path_) return false; const double current_w = angular_velocity_ptr_->z; - constexpr double color_r = 0.0 / 256.0; - constexpr double color_g = 148.0 / 256.0; - constexpr double color_b = 205.0 / 256.0; - constexpr double color_a = 0.999; + constexpr colorTuple debug_color = {0.0 / 256.0, 148.0 / 256.0, 205.0 / 256.0, 0.999}; + const std::string ns = "ego"; + const auto ego_path = generateEgoPath(current_v, current_w); const auto current_time = get_clock()->now(); - const auto ego_path = generateEgoPath(current_v, current_w, ego_polys); - std::vector objects; - createObjectData(ego_path, ego_polys, current_time, objects); - has_collision_ego = hasCollision(current_v, ego_path, objects); - std::string ns = "ego"; - addMarker( - current_time, ego_path, ego_polys, objects, color_r, color_g, color_b, color_a, ns, - debug_markers); - } + return check_collision(ego_path, debug_color, ns, current_time, filtered_objects); + }; - // step4. transform predicted trajectory from control module - bool has_collision_predicted = false; - if (use_predicted_trajectory_) { - std::vector predicted_polys; + // step4. make function to check collision with predicted trajectory from control module + const auto has_collision_predicted = + [&](pcl::PointCloud::Ptr filtered_objects) -> bool { + if (!use_predicted_trajectory_ || !predicted_traj_ptr_) return false; const auto predicted_traj_ptr = predicted_traj_ptr_; - constexpr double color_r = 0.0; - constexpr double color_g = 100.0 / 256.0; - constexpr double color_b = 0.0; - constexpr double color_a = 0.999; + const auto predicted_path_opt = generateEgoPath(*predicted_traj_ptr); + + if (!predicted_path_opt) return false; const auto current_time = predicted_traj_ptr->header.stamp; - const auto predicted_path_opt = generateEgoPath(*predicted_traj_ptr, predicted_polys); - if (predicted_path_opt) { - const auto & predicted_path = predicted_path_opt.value(); - std::vector objects; - createObjectData(predicted_path, predicted_polys, current_time, objects); - has_collision_predicted = hasCollision(current_v, predicted_path, objects); - - std::string ns = "predicted"; - addMarker( - current_time, predicted_path, predicted_polys, objects, color_r, color_g, color_b, color_a, - ns, debug_markers); - } - } + constexpr colorTuple debug_color = {0.0 / 256.0, 100.0 / 256.0, 0.0 / 256.0, 0.999}; + const std::string ns = "predicted"; + const auto & predicted_path = predicted_path_opt.value(); - return has_collision_ego || has_collision_predicted; + return check_collision(predicted_path, debug_color, ns, current_time, filtered_objects); + }; + + // Data of filtered point cloud + pcl::PointCloud::Ptr filtered_objects(new PointCloud); + // evaluate if there is a collision for both paths + const bool has_collision = + has_collision_ego(filtered_objects) || has_collision_predicted(filtered_objects); + + // Debug print + if (!filtered_objects->empty() && publish_debug_pointcloud_) { + const auto filtered_objects_ros_pointcloud_ptr_ = std::make_shared(); + pcl::toROSMsg(*filtered_objects, *filtered_objects_ros_pointcloud_ptr_); + pub_obstacle_pointcloud_->publish(*filtered_objects_ros_pointcloud_ptr_); + } + return has_collision; } -bool AEB::hasCollision( - const double current_v, const Path & ego_path, const std::vector & objects) +bool AEB::hasCollision(const double current_v, const ObjectData & closest_object) { - // calculate RSS - const auto current_p = tier4_autoware_utils::createPoint( - ego_path[0].position.x, ego_path[0].position.y, ego_path[0].position.z); + const double & obj_v = closest_object.velocity; const double & t = t_response_; - for (const auto & obj : objects) { - const double & obj_v = obj.velocity; - const double rss_dist = current_v * t + (current_v * current_v) / (2 * std::fabs(a_ego_min_)) - - obj_v * obj_v / (2 * std::fabs(a_obj_min_)) + longitudinal_offset_; - - // check the object is front the ego or not - if ((obj.position.x - ego_path[0].position.x) > 0) { - const double dist_ego_to_object = - motion_utils::calcSignedArcLength(ego_path, current_p, obj.position) - - vehicle_info_.max_longitudinal_offset_m; - if (dist_ego_to_object < rss_dist) { - // collision happens - ObjectData collision_data = obj; - collision_data.rss = rss_dist; - collision_data.distance_to_object = dist_ego_to_object; - collision_data_keeper_.update(collision_data); - return true; - } - } + const double rss_dist = current_v * t + (current_v * current_v) / (2 * std::fabs(a_ego_min_)) - + obj_v * obj_v / (2 * std::fabs(a_obj_min_)) + longitudinal_offset_; + if (closest_object.distance_to_object < rss_dist) { + // collision happens + ObjectData collision_data = closest_object; + collision_data.rss = rss_dist; + collision_data.distance_to_object = closest_object.distance_to_object; + collision_data_keeper_.update(collision_data); + return true; } return false; } -Path AEB::generateEgoPath( - const double curr_v, const double curr_w, std::vector & polygons) +Path AEB::generateEgoPath(const double curr_v, const double curr_w) { Path path; double curr_x = 0.0; @@ -444,17 +474,10 @@ Path AEB::generateEgoPath( } path.push_back(current_pose); } - - // generate ego polygons - polygons.resize(path.size() - 1); - for (size_t i = 0; i < path.size() - 1; ++i) { - polygons.at(i) = createPolygon(path.at(i), path.at(i + 1), vehicle_info_, expand_width_); - } return path; } -std::optional AEB::generateEgoPath( - const Trajectory & predicted_traj, std::vector & polygons) +std::optional AEB::generateEgoPath(const Trajectory & predicted_traj) { if (predicted_traj.points.empty()) { return std::nullopt; @@ -482,35 +505,82 @@ std::optional AEB::generateEgoPath( break; } } - // create polygon - polygons.resize(path.size()); + return path; +} + +std::vector AEB::generatePathFootprint( + const Path & path, const double extra_width_margin) +{ + std::vector polygons; for (size_t i = 0; i < path.size() - 1; ++i) { - polygons.at(i) = createPolygon(path.at(i), path.at(i + 1), vehicle_info_, expand_width_); + polygons.push_back( + createPolygon(path.at(i), path.at(i + 1), vehicle_info_, extra_width_margin)); } - return path; + return polygons; } -void AEB::createObjectData( - const Path & ego_path, const std::vector & ego_polys, - const rclcpp::Time & stamp, std::vector & objects) +void AEB::createObjectDataUsingPointCloudClusters( + const Path & ego_path, const std::vector & ego_polys, const rclcpp::Time & stamp, + std::vector & objects, const pcl::PointCloud::Ptr obstacle_points_ptr) { // check if the predicted path has valid number of points - if (ego_path.size() < 2 || ego_polys.empty()) { + if (ego_path.size() < 2 || ego_polys.empty() || obstacle_points_ptr->empty()) { return; } - PointCloud::Ptr obstacle_points_ptr(new PointCloud); - pcl::fromROSMsg(*obstacle_ros_pointcloud_ptr_, *obstacle_points_ptr); - for (const auto & point : obstacle_points_ptr->points) { + // eliminate noisy points by only considering points belonging to clusters of at least a certain + // size + const std::vector cluster_indices = std::invoke([&]() { + std::vector cluster_idx; + pcl::search::KdTree::Ptr tree(new pcl::search::KdTree); + tree->setInputCloud(obstacle_points_ptr); + pcl::EuclideanClusterExtraction ec; + ec.setClusterTolerance(cluster_tolerance_); + ec.setMinClusterSize(minimum_cluster_size_); + ec.setMaxClusterSize(maximum_cluster_size_); + ec.setSearchMethod(tree); + ec.setInputCloud(obstacle_points_ptr); + ec.extract(cluster_idx); + return cluster_idx; + }); + + PointCloud::Ptr points_belonging_to_cluster_hulls(new PointCloud); + for (const auto & indices : cluster_indices) { + PointCloud::Ptr cluster(new PointCloud); + for (const auto & index : indices.indices) { + cluster->push_back((*obstacle_points_ptr)[index]); + } + // Make a 2d convex hull for the objects + pcl::ConvexHull hull; + hull.setDimension(2); + hull.setInputCloud(cluster); + std::vector polygons; + PointCloud::Ptr surface_hull(new pcl::PointCloud); + hull.reconstruct(*surface_hull, polygons); + for (const auto & p : *surface_hull) { + points_belonging_to_cluster_hulls->push_back(p); + } + } + + // select points inside the ego footprint path + const auto current_p = tier4_autoware_utils::createPoint( + ego_path[0].position.x, ego_path[0].position.y, ego_path[0].position.z); + + for (const auto & p : *points_belonging_to_cluster_hulls) { + const auto obj_position = tier4_autoware_utils::createPoint(p.x, p.y, p.z); + const double dist_ego_to_object = + motion_utils::calcSignedArcLength(ego_path, current_p, obj_position) - + vehicle_info_.max_longitudinal_offset_m; + // objects behind ego are ignored + if (dist_ego_to_object < 0.0) continue; + ObjectData obj; obj.stamp = stamp; - obj.position = tier4_autoware_utils::createPoint(point.x, point.y, point.z); + obj.position = obj_position; obj.velocity = 0.0; - const Point2d obj_point(point.x, point.y); - const double lat_dist = motion_utils::calcLateralOffset(ego_path, obj.position); - if (lat_dist > 5.0) { - continue; - } + obj.distance_to_object = dist_ego_to_object; + + const Point2d obj_point(p.x, p.y); for (const auto & ego_poly : ego_polys) { if (bg::within(obj_point, ego_poly)) { objects.push_back(obj); @@ -520,6 +590,36 @@ void AEB::createObjectData( } } +void AEB::cropPointCloudWithEgoFootprintPath( + const std::vector & ego_polys, pcl::PointCloud::Ptr filtered_objects) +{ + PointCloud::Ptr full_points_ptr(new PointCloud); + pcl::fromROSMsg(*obstacle_ros_pointcloud_ptr_, *full_points_ptr); + // Create a Point cloud with the points of the ego footprint + PointCloud::Ptr path_polygon_points(new PointCloud); + std::for_each(ego_polys.begin(), ego_polys.end(), [&](const auto & poly) { + std::for_each(poly.outer().begin(), poly.outer().end(), [&](const auto & p) { + pcl::PointXYZ point(p.x(), p.y(), 0.0); + path_polygon_points->push_back(point); + }); + }); + // Make a surface hull with the ego footprint to filter out points + pcl::ConvexHull hull; + hull.setDimension(2); + hull.setInputCloud(path_polygon_points); + std::vector polygons; + pcl::PointCloud::Ptr surface_hull(new pcl::PointCloud); + hull.reconstruct(*surface_hull, polygons); + // Filter out points outside of the path's convex hull + pcl::CropHull path_polygon_hull_filter; + path_polygon_hull_filter.setDim(2); + path_polygon_hull_filter.setInputCloud(full_points_ptr); + path_polygon_hull_filter.setHullIndices(polygons); + path_polygon_hull_filter.setHullCloud(surface_hull); + path_polygon_hull_filter.filter(*filtered_objects); + filtered_objects->header.stamp = full_points_ptr->header.stamp; +} + void AEB::addMarker( const rclcpp::Time & current_time, const Path & path, const std::vector & polygons, const std::vector & objects, const double color_r, const double color_g, @@ -553,7 +653,7 @@ void AEB::addMarker( auto object_data_marker = tier4_autoware_utils::createDefaultMarker( "base_link", current_time, ns + "_objects", 0, Marker::SPHERE_LIST, - tier4_autoware_utils::createMarkerScale(0.05, 0.05, 0.05), + tier4_autoware_utils::createMarkerScale(0.5, 0.5, 0.5), tier4_autoware_utils::createMarkerColor(color_r, color_g, color_b, color_a)); for (const auto & e : objects) { object_data_marker.points.push_back(e.position); diff --git a/evaluator/perception_online_evaluator/CMakeLists.txt b/evaluator/perception_online_evaluator/CMakeLists.txt index e1cd0546ea94a..3d967ea6d86ce 100644 --- a/evaluator/perception_online_evaluator/CMakeLists.txt +++ b/evaluator/perception_online_evaluator/CMakeLists.txt @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME}_node SHARED src/metrics_calculator.cpp src/${PROJECT_NAME}_node.cpp src/metrics/deviation_metrics.cpp + src/metrics/detection_count.cpp src/utils/marker_utils.cpp src/utils/objects_filtering.cpp ) @@ -31,7 +32,7 @@ target_link_libraries(${PROJECT_NAME}_node glog::glog) if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_perception_online_evaluator_node.cpp - TIMEOUT 180 + TIMEOUT 300 ) target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}_node diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/perception_online_evaluator/README.md index de417d50dee53..7df375ac236d0 100644 --- a/evaluator/perception_online_evaluator/README.md +++ b/evaluator/perception_online_evaluator/README.md @@ -15,6 +15,9 @@ The evaluated metrics are as follows: - lateral_deviation - yaw_deviation - yaw_rate +- total_objects_count +- average_objects_count +- interval_objects_count ### Predicted Path Deviation / Predicted Path Deviation Variance @@ -89,6 +92,67 @@ Calculates the yaw rate of an object based on the change in yaw angle from the p ![yaw_rate](./images/yaw_rate.drawio.svg) +### Object Counts + +Counts the number of detections for each object class within the specified detection range. These metrics are measured for the most recent object not past objects. + +![detection_counts](./images/detection_counts.drawio.svg) + +In the provided illustration, the range $R$ is determined by a combination of lists of radii (e.g., $r_1, r_2, \ldots$) and heights (e.g., $h_1, h_2, \ldots$). +For example, + +- the number of CAR in range $R = (r_1, h_1)$ equals 1 +- the number of CAR in range $R = (r_1, h_2)$ equals 2 +- the number of CAR in range $R = (r_2, h_1)$ equals 3 +- the number of CAR in range $R = (r_2, h_2)$ equals 4 + +#### Total Object Count + +Counts the number of unique objects for each class within the specified detection range. The total object count is calculated as follows: + +$$ +\begin{align} +\text{Total Object Count (Class, Range)} = \left| \bigcup_{t=0}^{T_{\text{now}}} \{ \text{uuid} \mid \text{class}(t, \text{uuid}) = C \wedge \text{position}(t, \text{uuid}) \in R \} \right| +\end{align} +$$ + +where: + +- $\bigcup$ represents the union across all frames from $t = 0$ to $T_{\text{now}}$, which ensures that each uuid is counted only once. +- $\text{class}(t, \text{uuid}) = C$ specifies that the object with uuid at time $t$ belongs to class $C$. +- $\text{position}(t, \text{uuid}) \in R$ indicates that the object with uuid at time $t$ is within the specified range $R$. +- $\left| \{ \ldots \} \right|$ denotes the cardinality of the set, which counts the number of unique uuids that meet the class and range criteria across all considered times. + +#### Average Object Count + +Counts the average number of objects for each class within the specified detection range. This metric measures how many objects were detected in one frame, without considering uuids. The average object count is calculated as follows: + +$$ +\begin{align} +\text{Average Object Count (Class, Range)} = \frac{1}{N} \sum_{t=0}^{T_{\text{now}}} \left| \{ \text{object} \mid \text{class}(t, \text{object}) = C \wedge \text{position}(t, \text{object}) \in R \} \right| +\end{align} +$$ + +where: + +- $N$ represents the total number of frames within the time period time to $T\_{\text{now}}$ (it is precisely `detection_count_purge_seconds`) +- $text{object}$ denotes the number of objects that meet the class and range criteria at time $t$. + +#### Interval Object Count + +Counts the average number of objects for each class within the specified detection range over the last `objects_count_window_seconds`. This metric measures how many objects were detected in one frame, without considering uuids. The interval object count is calculated as follows: + +$$ +\begin{align} +\text{Interval Object Count (Class, Range)} = \frac{1}{W} \sum_{t=T_{\text{now}} - T_W}^{T_{\text{now}}} \left| \{ \text{object} \mid \text{class}(t, \text{object}) = C \wedge \text{position}(t, \text{object}) \in R \} \right| +\end{align} +$$ + +where: + +- $W$ represents the total number of frames within the last `objects_count_window_seconds`. +- $T_W$ represents the time window `objects_count_window_seconds` + ## Inputs / Outputs | Name | Type | Description | @@ -99,14 +163,24 @@ Calculates the yaw rate of an object based on the change in yaw angle from the p ## Parameters -| Name | Type | Description | -| --------------------------------- | ------------ | ------------------------------------------------------------------------------------------------ | -| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. | -| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. | -| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. | -| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped | -| `target_object.*.check_deviation` | bool | Whether to check deviation for specific object types (car, truck, etc.). | -| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). | +| Name | Type | Description | +| ------------------------------------------------------ | ------------ | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. | +| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. | +| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. | +| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped | +| `detection_radius_list` | list[double] | Detection radius for objects to be evaluated.(used for objects count only) | +| `detection_height_list` | list[double] | Detection height for objects to be evaluated. (used for objects count only) | +| `detection_count_purge_seconds` | double | Time window for purging object detection counts. | +| `objects_count_window_seconds` | double | Time window for keeping object detection counts. The number of object detections within this time window is stored in `detection_count_vector_` | +| `target_object.*.check_lateral_deviation` | bool | Whether to check lateral deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_yaw_deviation` | bool | Whether to check yaw deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_predicted_path_deviation` | bool | Whether to check predicted path deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_yaw_rate` | bool | Whether to check yaw rate for specific object types (car, truck, etc.). | +| `target_object.*.check_total_objects_count` | bool | Whether to check total object count for specific object types (car, truck, etc.). | +| `target_object.*.check_average_objects_count` | bool | Whether to check average object count for specific object types (car, truck, etc.). | +| `target_object.*.check_interval_average_objects_count` | bool | Whether to check interval average object count for specific object types (car, truck, etc.). | +| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). | ## Assumptions / Known limits diff --git a/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg b/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg new file mode 100644 index 0000000000000..f6dc7431e7ae6 --- /dev/null +++ b/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg @@ -0,0 +1,445 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `r_2` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `r_1` +
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `h_1` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `h_2` +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
diff --git a/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg b/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg index 20587ec30d683..eeabd7dca8d43 100644 --- a/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg +++ b/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg @@ -5,10 +5,10 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="283px" + width="365px" height="77px" - viewBox="-0.5 -0.5 283 77" - content="<mxfile host="app.diagrams.net" modified="2024-04-15T16:43:48.109Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/122.0.0.0 Safari/537.36" version="24.2.5" etag="-1Cxl0cC8cre4wtqPdY1" type="google" scale="1" border="0"> <diagram name="ページ1" id="hj15VFmwux7EVVTqehov"> <mxGraphModel dx="-203" dy="1514" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="0" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="1" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="2" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-180;" vertex="1" parent="1"> <mxGeometry x="955" y="-534" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="3" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-210;" vertex="1" parent="1"> <mxGeometry x="1120" y="-540" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="4" value="`t_2`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1120" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="5" value="`t_1`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="955" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="6" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="967" y="-520" as="sourcePoint" /> <mxPoint x="1030" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="7" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1189" y="-551" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="8" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;dashed=1;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1197" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="9" value="" style="endArrow=classic;html=1;rounded=0;curved=1;endFill=1;endSize=2;strokeColor=#000000;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1181" y="-520" as="sourcePoint" /> <mxPoint x="1178" y="-545" as="targetPoint" /> <Array as="points"> <mxPoint x="1182" y="-533" /> </Array> </mxGeometry> </mxCell> <mxCell id="10" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\Deltayaw`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1168" y="-549" width="70" height="30" as="geometry" /> </mxCell> <mxCell id="11" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1060" y="-519.92" as="sourcePoint" /> <mxPoint x="1095" y="-519.92" as="targetPoint" /> </mxGeometry> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " + viewBox="-0.5 -0.5 365 77" + content="<mxfile host="app.diagrams.net" modified="2024-04-18T12:50:45.453Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/122.0.0.0 Safari/537.36" version="24.2.5" etag="KrfeBttdqJpC7U2PhJCb" type="google" scale="1" border="0"> <diagram name="ページ1" id="3M-pu1oXXIi-LJN1ZMRq"> <mxGraphModel dx="722" dy="2026" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="0" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="1" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="2" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-180;" vertex="1" parent="1"> <mxGeometry x="955" y="-534" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="3" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-210;" vertex="1" parent="1"> <mxGeometry x="1120" y="-540" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="4" value="`t_2`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1120" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="5" value="`t_1`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="955" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="6" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="967" y="-520" as="sourcePoint" /> <mxPoint x="1030" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="7" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1189" y="-551" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="8" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;dashed=1;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1197" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="9" value="" style="endArrow=classic;html=1;rounded=0;curved=1;endFill=1;endSize=2;strokeColor=#000000;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1181" y="-520" as="sourcePoint" /> <mxPoint x="1178" y="-545" as="targetPoint" /> <Array as="points"> <mxPoint x="1182" y="-533" /> </Array> </mxGeometry> </mxCell> <mxCell id="10" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\Deltayaw`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1168" y="-549" width="70" height="30" as="geometry" /> </mxCell> <mxCell id="11" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\omega_{yaw} = (\Delta yaw) / (t2-t1)`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1130" y="-511" width="190" height="30" as="geometry" /> </mxCell> <mxCell id="12" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1060" y="-519.92" as="sourcePoint" /> <mxPoint x="1095" y="-519.92" as="targetPoint" /> </mxGeometry> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " >