From 01e78a16ecc4346c4b0137748281b3b841145001 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 14 Nov 2024 12:39:35 +0900 Subject: [PATCH 001/273] fix(bvp): remove callback group (#9294) Signed-off-by: satoshi-ota --- .../src/node.cpp | 17 +---------------- 1 file changed, 1 insertion(+), 16 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index 93473402ebc9c..394412a508d41 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -38,20 +38,6 @@ #include #include -namespace -{ -rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr) -{ - rclcpp::CallbackGroup::SharedPtr callback_group = - node_ptr->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - - auto sub_opt = rclcpp::SubscriptionOptions(); - sub_opt.callback_group = callback_group; - - return sub_opt; -} -} // namespace - namespace autoware::behavior_velocity_planner { namespace @@ -80,8 +66,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio // Trigger Subscriber trigger_sub_path_with_lane_id_ = this->create_subscription( - "~/input/path_with_lane_id", 1, std::bind(&BehaviorVelocityPlannerNode::onTrigger, this, _1), - createSubscriptionOptions(this)); + "~/input/path_with_lane_id", 1, std::bind(&BehaviorVelocityPlannerNode::onTrigger, this, _1)); srv_load_plugin_ = create_service( "~/service/load_plugin", std::bind(&BehaviorVelocityPlannerNode::onLoadPlugin, this, _1, _2)); From 7eec0bbae2003103ec835de162722e51acf95a88 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 14 Nov 2024 13:32:30 +0900 Subject: [PATCH 002/273] fix(run_out): output velocity factor (#9319) * fix(run_out): output velocity factor Signed-off-by: satoshi-ota * fix(adapi): subscribe run out velocity factor Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/scene.cpp | 10 +++++++++- system/autoware_default_adapi/src/planning.cpp | 1 + 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index 5a219f654561a..2296655d700d3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -50,7 +50,7 @@ RunOutModule::RunOutModule( debug_ptr_(debug_ptr), state_machine_(std::make_unique(planner_param.approaching.state)) { - velocity_factor_.init(PlanningBehavior::UNKNOWN); + velocity_factor_.init(PlanningBehavior::ROUTE_OBSTACLE); if (planner_param.run_out.use_partition_lanelet) { const lanelet::LaneletMapConstPtr & ll = planner_data->route_handler_->getLaneletMapPtr(); @@ -768,6 +768,11 @@ bool RunOutModule::insertStopPoint( stop_point_with_lane_id = path.points.at(nearest_seg_idx); stop_point_with_lane_id.point.pose = *stop_point; planning_utils::insertVelocity(path, stop_point_with_lane_id, 0.0, insert_idx); + + velocity_factor_.set( + path.points, planner_data_->current_odometry->pose, stop_point.value(), VelocityFactor::UNKNOWN, + "run_out"); + return true; } @@ -870,6 +875,9 @@ void RunOutModule::insertApproachingVelocity( return; } + velocity_factor_.set( + output_path.points, current_pose, stop_point.value(), VelocityFactor::UNKNOWN, "run_out"); + // debug debug_ptr_->pushStopPose(autoware::universe_utils::calcOffsetPose( *stop_point, planner_param_.vehicle_param.base_to_front, 0, 0)); diff --git a/system/autoware_default_adapi/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp index 49c4e8f432de6..4ff0edfd2b7d5 100644 --- a/system/autoware_default_adapi/src/planning.cpp +++ b/system/autoware_default_adapi/src/planning.cpp @@ -81,6 +81,7 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning "/planning/velocity_factors/obstacle_stop", "/planning/velocity_factors/obstacle_cruise", "/planning/velocity_factors/occlusion_spot", + "/planning/velocity_factors/run_out", "/planning/velocity_factors/stop_line", "/planning/velocity_factors/surround_obstacle", "/planning/velocity_factors/traffic_light", From 6e1c3aa807866f432bd66b8fdedc901c30b67c1a Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Thu, 14 Nov 2024 15:35:47 +0900 Subject: [PATCH 003/273] fix(codeowner): fix codeowner file's directory name (#9321) fix codeowner Signed-off-by: Y.Hisaki --- .github/CODEOWNERS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 6e83e2b52fdbe..579b60a5be77f 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -22,7 +22,7 @@ common/autoware_signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.j common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -common/autoware_trajectory_container/** yukinari.hisaki.2@tier4.jp takayuki.murooka@tier4.jp mamoru.sobue@tier4.jp +common/autoware_trajectory/** yukinari.hisaki.2@tier4.jp takayuki.murooka@tier4.jp mamoru.sobue@tier4.jp common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp From 7528c4738398b5f58e0582f0b065c4ee14da6ad7 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Thu, 14 Nov 2024 17:27:44 +0900 Subject: [PATCH 004/273] feat(behavior_velocity_planner): replace first_stop_path_point_index (#9296) * feat(behavior_velocity_planner): replace first_stop_path_point_index Signed-off-by: Y.Hisaki * add const Signed-off-by: Y.Hisaki * Update planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp Co-authored-by: Kosuke Takeuchi * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp Co-authored-by: Kosuke Takeuchi --------- Signed-off-by: Y.Hisaki Co-authored-by: Kosuke Takeuchi --- .../src/scene.cpp | 9 ++++---- .../src/scene_no_stopping_area.cpp | 12 +++++----- .../src/planner_manager.cpp | 22 +++++++++++++------ .../plugin_interface.hpp | 2 +- .../plugin_wrapper.hpp | 4 ++-- .../scene_module_interface.hpp | 9 ++++---- .../src/scene_module_interface.cpp | 6 ++--- .../src/scene.cpp | 5 +++-- .../src/manager.cpp | 9 +++++--- .../src/scene.cpp | 9 +++++--- 10 files changed, 53 insertions(+), 34 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp index afbff7425542a..abbb818f2b042 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp @@ -195,13 +195,14 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason * // Create legacy StopReason { - const auto insert_idx = stop_point->first + 1; + const double stop_path_point_distance = autoware::motion_utils::calcSignedArcLength( + path->points, 0, stop_pose.position, stop_point->first); if ( - !first_stop_path_point_index_ || - static_cast(insert_idx) < first_stop_path_point_index_) { + !first_stop_path_point_distance_ || + stop_path_point_distance < first_stop_path_point_distance_.value()) { debug_data_.first_stop_pose = stop_point->second; - first_stop_path_point_index_ = static_cast(insert_idx); + first_stop_path_point_distance_ = stop_path_point_distance; } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index 031f2976da0a7..bac91d6ca92fd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -153,12 +153,14 @@ bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason // Create legacy StopReason { - const auto insert_idx = stop_point->first + 1; + const double stop_path_point_distance = autoware::motion_utils::calcSignedArcLength( + path->points, 0, stop_pose.position, stop_point->first); + if ( - !first_stop_path_point_index_ || - static_cast(insert_idx) < first_stop_path_point_index_) { - debug_data_.first_stop_pose = stop_pose; - first_stop_path_point_index_ = static_cast(insert_idx); + !first_stop_path_point_distance_ || + stop_path_point_distance < first_stop_path_point_distance_.value()) { + debug_data_.first_stop_pose = stop_point->second; + first_stop_path_point_distance_ = stop_path_point_distance; } } } else if (state_machine_.getState() == StateMachine::State::GO) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp index 4a55ba5c1c666..05aa4868249f3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp @@ -14,9 +14,13 @@ #include "planner_manager.hpp" +#include +#include + #include #include +#include #include namespace autoware::behavior_velocity_planner @@ -103,24 +107,28 @@ tier4_planning_msgs::msg::PathWithLaneId BehaviorVelocityPlannerManager::planPat { tier4_planning_msgs::msg::PathWithLaneId output_path_msg = input_path_msg; - int first_stop_path_point_index = static_cast(output_path_msg.points.size() - 1); + double first_stop_path_point_distance = + autoware::motion_utils::calcArcLength(output_path_msg.points); std::string stop_reason_msg("path_end"); for (const auto & plugin : scene_manager_plugins_) { plugin->updateSceneModuleInstances(planner_data, input_path_msg); plugin->plan(&output_path_msg); - const auto firstStopPathPointIndex = plugin->getFirstStopPathPointIndex(); + const std::optional firstStopPathPointDistance = + plugin->getFirstStopPathPointDistance(); - if (firstStopPathPointIndex) { - if (firstStopPathPointIndex.value() < first_stop_path_point_index) { - first_stop_path_point_index = firstStopPathPointIndex.value(); + if (firstStopPathPointDistance.has_value()) { + if (firstStopPathPointDistance.value() < first_stop_path_point_distance) { + first_stop_path_point_distance = firstStopPathPointDistance.value(); stop_reason_msg = plugin->getModuleName(); } } } - stop_reason_diag_ = makeStopReasonDiag( - stop_reason_msg, output_path_msg.points[first_stop_path_point_index].point.pose); + const geometry_msgs::msg::Pose stop_pose = autoware::motion_utils::calcInterpolatedPose( + output_path_msg.points, first_stop_path_point_distance); + + stop_reason_diag_ = makeStopReasonDiag(stop_reason_msg, stop_pose); return output_path_msg; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_interface.hpp index b163cd31e3030..5f6549f1e4492 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_interface.hpp @@ -34,7 +34,7 @@ class PluginInterface virtual void updateSceneModuleInstances( const std::shared_ptr & planner_data, const tier4_planning_msgs::msg::PathWithLaneId & path) = 0; - virtual std::optional getFirstStopPathPointIndex() = 0; + virtual std::optional getFirstStopPathPointDistance() = 0; virtual const char * getModuleName() = 0; }; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_wrapper.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_wrapper.hpp index 0e32ff958c0a5..0392bf24d3a36 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_wrapper.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_wrapper.hpp @@ -38,9 +38,9 @@ class PluginWrapper : public PluginInterface { scene_manager_->updateSceneModuleInstances(planner_data, path); } - std::optional getFirstStopPathPointIndex() override + std::optional getFirstStopPathPointDistance() override { - return scene_manager_->getFirstStopPathPointIndex(); + return scene_manager_->getFirstStopPathPointDistance(); } const char * getModuleName() override { return scene_manager_->getModuleName(); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index 705062e35885b..e39cfb3a5144d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -37,6 +37,7 @@ #include #include +#include #include #include #include @@ -115,7 +116,7 @@ class SceneModuleInterface std::shared_ptr getTimeKeeper() { return time_keeper_; } - std::optional getFirstStopPathPointIndex() { return first_stop_path_point_index_; } + std::optional getFirstStopPathPointDistance() { return first_stop_path_point_distance_; } void setActivation(const bool activated) { activated_ = activated; } void setRTCEnabled(const bool enable_rtc) { rtc_enabled_ = enable_rtc; } @@ -138,7 +139,7 @@ class SceneModuleInterface rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; std::optional infrastructure_command_; - std::optional first_stop_path_point_index_; + std::optional first_stop_path_point_distance_; autoware::motion_utils::VelocityFactorInterface velocity_factor_; std::vector objects_of_interest_; mutable std::shared_ptr time_keeper_; @@ -173,7 +174,7 @@ class SceneModuleManagerInterface virtual const char * getModuleName() = 0; - std::optional getFirstStopPathPointIndex() { return first_stop_path_point_index_; } + std::optional getFirstStopPathPointDistance() { return first_stop_path_point_distance_; } void updateSceneModuleInstances( const std::shared_ptr & planner_data, @@ -207,7 +208,7 @@ class SceneModuleManagerInterface std::shared_ptr planner_data_; autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator_; - std::optional first_stop_path_point_index_; + std::optional first_stop_path_point_distance_; rclcpp::Node & node_; rclcpp::Clock::SharedPtr clock_; // Debug diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index ba7a0bee2851e..2d014d4bbf81d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -117,7 +117,7 @@ void SceneModuleManagerInterface::modifyPathVelocity( tier4_v2x_msgs::msg::InfrastructureCommandArray infrastructure_command_array; infrastructure_command_array.stamp = clock_->now(); - first_stop_path_point_index_ = static_cast(path->points.size()) - 1; + first_stop_path_point_distance_ = autoware::motion_utils::calcArcLength(path->points); for (const auto & scene_module : scene_modules_) { tier4_planning_msgs::msg::StopReason stop_reason; scene_module->resetVelocityFactor(); @@ -137,8 +137,8 @@ void SceneModuleManagerInterface::modifyPathVelocity( infrastructure_command_array.commands.push_back(*command); } - if (scene_module->getFirstStopPathPointIndex() < first_stop_path_point_index_) { - first_stop_path_point_index_ = scene_module->getFirstStopPathPointIndex(); + if (scene_module->getFirstStopPathPointDistance() < first_stop_path_point_distance_) { + first_stop_path_point_distance_ = scene_module->getFirstStopPathPointDistance(); } for (const auto & marker : scene_module->createDebugMarkerArray().markers) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index 50b85613ef08f..0500d22d425cd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -48,7 +48,7 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop if (path->points.empty()) return true; const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; debug_data_.base_link2front = base_link2front; - first_stop_path_point_index_ = static_cast(path->points.size()) - 1; + first_stop_path_point_distance_ = autoware::motion_utils::calcArcLength(path->points); *stop_reason = planning_utils::initializeStopReason(StopReason::STOP_LINE); const LineString2d stop_line = planning_utils::extendLine( @@ -91,7 +91,8 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop planning_utils::insertStopPoint(stop_pose.position, stop_line_seg_idx, *path); // Update first stop index - first_stop_path_point_index_ = static_cast(stop_point_idx); + first_stop_path_point_distance_ = autoware::motion_utils::calcSignedArcLength( + path->points, 0, stop_pose.position, stop_line_seg_idx); debug_data_.stop_pose = stop_pose; // Get stop point and stop factor diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp index eddc30657a0df..0d7c77d5e1b59 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp @@ -15,6 +15,7 @@ #include "manager.hpp" #include +#include #include #include @@ -60,7 +61,7 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat stop_reason_array.header.frame_id = "map"; stop_reason_array.header.stamp = path->header.stamp; - first_stop_path_point_index_ = static_cast(path->points.size() - 1); + first_stop_path_point_distance_ = autoware::motion_utils::calcArcLength(path->points); nearest_ref_stop_path_point_index_ = static_cast(path->points.size() - 1); for (const auto & scene_module : scene_modules_) { tier4_planning_msgs::msg::StopReason stop_reason; @@ -79,8 +80,10 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat stop_reason_array.stop_reasons.emplace_back(stop_reason); } - if (traffic_light_scene_module->getFirstStopPathPointIndex() < first_stop_path_point_index_) { - first_stop_path_point_index_ = traffic_light_scene_module->getFirstStopPathPointIndex(); + if ( + traffic_light_scene_module->getFirstStopPathPointDistance() < + first_stop_path_point_distance_) { + first_stop_path_point_distance_ = traffic_light_scene_module->getFirstStopPathPointDistance(); } if ( traffic_light_scene_module->getFirstRefStopPathPointIndex() < diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index af5eac943ec13..4b17f95358be6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -58,7 +58,7 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * { debug_data_ = DebugData(); debug_data_.base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; - first_stop_path_point_index_ = static_cast(path->points.size()) - 1; + first_stop_path_point_distance_ = autoware::motion_utils::calcArcLength(path->points); first_ref_stop_path_point_index_ = static_cast(path->points.size()) - 1; *stop_reason = planning_utils::initializeStopReason(StopReason::TRAFFIC_LIGHT); @@ -291,8 +291,11 @@ tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose( // Insert stop pose into path or replace with zero velocity size_t insert_index = insert_target_point_idx; planning_utils::insertVelocity(modified_path, target_point_with_lane_id, 0.0, insert_index); - if (static_cast(target_velocity_point_idx) < first_stop_path_point_index_) { - first_stop_path_point_index_ = static_cast(target_velocity_point_idx); + + const double target_velocity_point_distance = autoware::motion_utils::calcArcLength(std::vector( + modified_path.points.begin(), modified_path.points.begin() + target_velocity_point_idx)); + if (target_velocity_point_distance < first_stop_path_point_distance_) { + first_stop_path_point_distance_ = target_velocity_point_distance; debug_data_.first_stop_pose = target_point_with_lane_id.point.pose; } From 4e12cb06c3fd735810922a7fbe68c298272e8455 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Thu, 14 Nov 2024 18:57:16 +0900 Subject: [PATCH 005/273] feat(run_out_module): add tests to run out (#9222) * WIP add tests for utils and path_utils Signed-off-by: Daniel Sanchez * add tests for utils and fix test path utils Signed-off-by: Daniel Sanchez * dynamic obstacles Signed-off-by: Daniel Sanchez * new tests and add function declarations Signed-off-by: Daniel Sanchez * add points for test of extractObstaclePointsWithinPolygon Signed-off-by: Daniel Sanchez * add state machine tests and other tests for dynamic obstacle Signed-off-by: Daniel Sanchez * remove unused test checks Signed-off-by: Daniel Sanchez * remove unused tests Signed-off-by: Daniel Sanchez * remove unwanted semicolons Signed-off-by: Daniel Sanchez * test Signed-off-by: Daniel Sanchez * add comments Signed-off-by: Daniel Sanchez * solve cpp-check limitation issue by removing namespaces Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../CMakeLists.txt | 15 + .../package.xml | 1 + .../src/dynamic_obstacle.cpp | 10 +- .../src/dynamic_obstacle.hpp | 53 +++ .../src/path_utils.cpp | 3 + .../src/utils.cpp | 8 +- .../src/utils.hpp | 3 +- .../tests/test_dynamic_obstacle.cpp | 404 ++++++++++++++++++ .../tests/test_path_utils.cpp | 71 +++ .../tests/test_state_machine.cpp | 107 +++++ .../tests/test_utils.cpp | 302 +++++++++++++ 11 files changed, 962 insertions(+), 15 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_dynamic_obstacle.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_path_utils.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_state_machine.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_utils.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CMakeLists.txt index bcbe4ea12a643..da2f4ce33ff60 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CMakeLists.txt @@ -15,4 +15,19 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/path_utils.cpp ) +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + tests/test_dynamic_obstacle.cpp + tests/test_path_utils.cpp + tests/test_utils.cpp + tests/test_state_machine.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + autoware_behavior_velocity_run_out_module + ) + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + + + ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml index 369b5fba81122..6aaab5817aad6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml @@ -41,6 +41,7 @@ tf2_ros visualization_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp index f75da2b5cc5de..74b1ca490f752 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp @@ -32,8 +32,7 @@ namespace autoware::behavior_velocity_planner { -namespace -{ + // create quaternion facing to the nearest trajectory point geometry_msgs::msg::Quaternion createQuaternionFacingToTrajectory( const PathPointsWithLaneId & path_points, const geometry_msgs::msg::Point & point) @@ -114,10 +113,7 @@ pcl::PointCloud applyVoxelGridFilter( bool isAheadOf( const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Pose & base_pose) { - const auto longitudinal_deviation = - autoware::universe_utils::calcLongitudinalDeviation(base_pose, target_point); - const bool is_ahead = longitudinal_deviation > 0; - return is_ahead; + return autoware::universe_utils::calcLongitudinalDeviation(base_pose, target_point) > 0; } pcl::PointCloud extractObstaclePointsWithinPolygon( @@ -349,8 +345,6 @@ std::vector createPathToPredictionTime( return path_to_prediction_time; } -} // namespace - DynamicObstacleCreatorForObject::DynamicObstacleCreatorForObject( rclcpp::Node & node, std::shared_ptr & debug_ptr, const DynamicObstacleParam & param) : DynamicObstacleCreator(node, debug_ptr, param) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp index c1d59794a30fe..6b4050fe9bfbb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp @@ -40,6 +40,7 @@ #include #include +#include #include namespace autoware::behavior_velocity_planner @@ -171,6 +172,58 @@ class DynamicObstacleCreatorForPoints : public DynamicObstacleCreator pcl::PointCloud obstacle_points_map_filtered_; }; +geometry_msgs::msg::Quaternion createQuaternionFacingToTrajectory( + const PathPointsWithLaneId & path_points, const geometry_msgs::msg::Point & point); + +std::vector createPredictedPath( + const geometry_msgs::msg::Pose & initial_pose, const float time_step, + const float max_velocity_mps, const float max_prediction_time); + +pcl::PointCloud applyVoxelGridFilter( + const pcl::PointCloud & input_points); + +pcl::PointCloud applyVoxelGridFilter( + const sensor_msgs::msg::PointCloud2 & input_points); + +bool isAheadOf( + const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Pose & base_pose); + +pcl::PointCloud extractObstaclePointsWithinPolygon( + const pcl::PointCloud & input_points, const Polygons2d & polys); + +std::vector> groupPointsWithNearestSegmentIndex( + const pcl::PointCloud & input_points, const PathPointsWithLaneId & path_points); + +pcl::PointXYZ calculateLateralNearestPoint( + const pcl::PointCloud & input_points, const geometry_msgs::msg::Pose & base_pose); + +pcl::PointCloud selectLateralNearestPoints( + const std::vector> & points_with_index, + const PathPointsWithLaneId & path_points); + +pcl::PointCloud extractLateralNearestPoints( + const pcl::PointCloud & input_points, const PathWithLaneId & path, + const float interval); + +std::optional getTransformMatrix( + const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id, + const std::string & source_frame_id, const builtin_interfaces::msg::Time & stamp); + +pcl::PointCloud transformPointCloud( + const PointCloud2 & input_pointcloud, const Eigen::Affine3f & transform_matrix); + +PointCloud2 concatPointCloud( + const pcl::PointCloud & cloud1, const pcl::PointCloud & cloud2); + +void calculateMinAndMaxVelFromCovariance( + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance, + const double std_dev_multiplier, run_out_utils::DynamicObstacle & dynamic_obstacle); + +double convertDurationToDouble(const builtin_interfaces::msg::Duration & duration); + +std::vector createPathToPredictionTime( + const autoware_perception_msgs::msg::PredictedPath & predicted_path, double prediction_time); + } // namespace autoware::behavior_velocity_planner #endif // DYNAMIC_OBSTACLE_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp index 2196cdec36886..cf3c0fd7e10e1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp @@ -17,6 +17,9 @@ #include namespace autoware::behavior_velocity_planner::run_out_utils { +/** + * This function returns the point with the smallest (signed) longitudinal distance + */ geometry_msgs::msg::Point findLongitudinalNearestPoint( const std::vector & points, const geometry_msgs::msg::Point & src_point, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp index 151d2616da5f9..c32d38da2db33 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp @@ -127,11 +127,7 @@ std::vector findLateralSameSidePoints( bool isSamePoint(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2) { - if (autoware::universe_utils::calcDistance2d(p1, p2) < std::numeric_limits::epsilon()) { - return true; - } - - return false; + return (autoware::universe_utils::calcDistance2d(p1, p2) < std::numeric_limits::epsilon()); } // insert path velocity which doesn't exceed original velocity @@ -230,7 +226,7 @@ PathPointsWithLaneId decimatePathPoints( const PathPointsWithLaneId & input_path_points, const float step) { if (input_path_points.empty()) { - return PathPointsWithLaneId(); + return {}; } float dist_sum = 0.0; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp index af6d9a7bc631b..1f948cc7faaa1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.hpp @@ -255,7 +255,8 @@ std::optional> createDetectionAreaPolygon // extend path to the pose of goal PathWithLaneId extendPath(const PathWithLaneId & input, const double extend_distance); -PathPoint createExtendPathPoint(const double extend_distance, const PathPoint & goal_point); +PathPointWithLaneId createExtendPathPoint( + const double extend_distance, const PathPointWithLaneId & goal_point); DetectionMethod toEnum(const std::string & detection_method); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_dynamic_obstacle.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_dynamic_obstacle.cpp new file mode 100644 index 0000000000000..e6a838c77fb37 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_dynamic_obstacle.cpp @@ -0,0 +1,404 @@ +// 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 "debug.hpp" +#include "dynamic_obstacle.hpp" +#include "path_utils.hpp" +#include "scene.hpp" +#include "utils.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +using autoware::universe_utils::Point2d; +using autoware::universe_utils::Polygon2d; +using autoware_perception_msgs::msg::ObjectClassification; +using geometry_msgs::msg::Point; +using Polygons2d = std::vector; + +using tier4_planning_msgs::msg::PathPointWithLaneId; +using tier4_planning_msgs::msg::PathWithLaneId; +using PathPointsWithLaneId = std::vector; + +using autoware::behavior_velocity_planner::applyVoxelGridFilter; +using autoware::behavior_velocity_planner::createPredictedPath; +using autoware::behavior_velocity_planner::createQuaternionFacingToTrajectory; +using autoware::behavior_velocity_planner::extractLateralNearestPoints; +using autoware::behavior_velocity_planner::extractObstaclePointsWithinPolygon; +using autoware::behavior_velocity_planner::groupPointsWithNearestSegmentIndex; + +using autoware::behavior_velocity_planner::calculateLateralNearestPoint; +using autoware::behavior_velocity_planner::calculateMinAndMaxVelFromCovariance; +using autoware::behavior_velocity_planner::concatPointCloud; +using autoware::behavior_velocity_planner::convertDurationToDouble; +using autoware::behavior_velocity_planner::createPathToPredictionTime; +using autoware::behavior_velocity_planner::DynamicObstacle; +using autoware::behavior_velocity_planner::DynamicObstacleCreatorForObject; +using autoware::behavior_velocity_planner::DynamicObstacleCreatorForObjectWithoutPath; +using autoware::behavior_velocity_planner::DynamicObstacleCreatorForPoints; +using autoware::behavior_velocity_planner::DynamicObstacleParam; +using autoware::behavior_velocity_planner::isAheadOf; +using autoware::behavior_velocity_planner::PointCloud2; +using autoware::behavior_velocity_planner::RunOutDebug; +using autoware::behavior_velocity_planner::selectLateralNearestPoints; +using autoware::behavior_velocity_planner::transformPointCloud; +using autoware::behavior_velocity_planner::run_out_utils::createExtendPathPoint; + +class TestDynamicObstacleMethods : public ::testing::Test +{ + void SetUp() override {} +}; + +class TestDynamicObstacle : public ::testing::Test +{ + void SetUp() override { init_param(); } + + void init_param() + { + auto node_options = rclcpp::NodeOptions{}; + node_ptr_ = std::make_shared(name_, node_options); + debug_ptr_ = std::make_shared(*node_ptr_); + object_creator_for_points_ = + std::make_shared(*node_ptr_, debug_ptr_, param_); + object_creator_for_objects_ = + std::make_shared(*node_ptr_, debug_ptr_, param_); + object_creator_for_objects_without_path_ = + std::make_shared(*node_ptr_, debug_ptr_, param_); + } + std::string name_{"test_dynamic_obstacle_creators"}; + + std::shared_ptr object_creator_for_points_; + std::shared_ptr object_creator_for_objects_; + std::shared_ptr + object_creator_for_objects_without_path_; + DynamicObstacleParam param_; + std::shared_ptr debug_ptr_; + std::shared_ptr node_ptr_; +}; + +pcl::PointCloud generate_pointcloud( + const size_t number_points_in_axis, const double resolution) +{ + pcl::PointCloud point_cloud; + for (size_t i = 0; i < number_points_in_axis; ++i) { + for (size_t j = 0; j < number_points_in_axis; ++j) { + for (size_t k = 0; k < number_points_in_axis; ++k) { + pcl::PointXYZ p; + p.x = i * resolution; + p.y = j * resolution; + p.z = k * resolution; + point_cloud.push_back(p); + } + } + } + return point_cloud; +}; + +TEST_F(TestDynamicObstacleMethods, testCreateQuaternionFacingToTrajectory) +{ + constexpr size_t n_path_points{10}; + PathPointsWithLaneId path; + PathPointWithLaneId base_point; + for (size_t i = 0; i < n_path_points; ++i) { + const PathPointWithLaneId p = createExtendPathPoint(static_cast(i), base_point); + path.push_back(p); + } + + /* + path + | ^ x + | | + | y | + | <------- ref frame + | + | + (2.0,0.0) |<------0 (2.0,-2.0) point + | ^ + | | + | 90 deg yaw + */ + + { + geometry_msgs::msg::Point point; + point.x = 2.0; + point.y = -2.0; + + const auto quaternion_facing_traj = createQuaternionFacingToTrajectory(path, point); + const auto rpy = autoware::universe_utils::getRPY(quaternion_facing_traj); + const auto yaw = autoware::universe_utils::normalizeRadian(rpy.z); + EXPECT_DOUBLE_EQ(yaw, M_PI_2); + geometry_msgs::msg::Pose geom_base_point; + geom_base_point.position = base_point.point.pose.position; + EXPECT_TRUE(isAheadOf(point, geom_base_point)); + } + + { + geometry_msgs::msg::Point point; + point.x = 2.75; // path resolution is 1.0, this makes sure the point is "behind" the closest + // point on the path. + point.y = -0.25; + + const auto quaternion_facing_traj = createQuaternionFacingToTrajectory(path, point); + const auto rpy = autoware::universe_utils::getRPY(quaternion_facing_traj); + const auto yaw = autoware::universe_utils::normalizeRadian(rpy.z); + EXPECT_DOUBLE_EQ(std::abs(yaw), M_PI_2); + geometry_msgs::msg::Pose geom_base_point; + geom_base_point.position = base_point.point.pose.position; + EXPECT_TRUE(isAheadOf(point, geom_base_point)); + } +} + +TEST_F(TestDynamicObstacleMethods, testCreatePredictedPath) +{ + using autoware::behavior_velocity_planner::run_out_utils::isSamePoint; + + constexpr float time_step{0.1}; + constexpr float max_velocity_mps{3.0}; + constexpr float max_prediction_time{5.0}; + geometry_msgs::msg::Pose initial_pose; + + const auto traj = + createPredictedPath(initial_pose, time_step, max_velocity_mps, max_prediction_time); + EXPECT_EQ(traj.size(), static_cast(max_prediction_time / time_step)); + auto last_pose = traj.back(); + geometry_msgs::msg::Point expected_point; + expected_point.x = max_prediction_time * max_velocity_mps - time_step * max_velocity_mps; + EXPECT_TRUE(std::abs(expected_point.x - last_pose.position.x) < 1e-3); +} + +TEST_F(TestDynamicObstacleMethods, testApplyVoxelGridFilter) +{ + pcl::PointCloud point_cloud = generate_pointcloud(10, 0.025); + + { + auto filtered_point_cloud = applyVoxelGridFilter(point_cloud); + EXPECT_FALSE(filtered_point_cloud.empty()); + EXPECT_TRUE(filtered_point_cloud.size() < point_cloud.size()); + const bool points_have_no_height = std::all_of( + filtered_point_cloud.begin(), filtered_point_cloud.end(), + [](const auto & p) { return std::abs(p.z) < std::numeric_limits::epsilon(); }); + EXPECT_TRUE(points_have_no_height); + + Polygons2d polys; + const auto empty_cloud = extractObstaclePointsWithinPolygon(filtered_point_cloud, polys); + EXPECT_TRUE(empty_cloud.empty()); + + Polygon2d poly; + Point2d p1; + p1.x() = 1.0; + p1.y() = 0.0; + + Point2d p2; + p2.x() = -1.0; + p2.y() = 2.0; + + Point2d p3; + p3.x() = -1.0; + p3.y() = -2.0; + poly.outer().push_back(p1); + poly.outer().push_back(p2); + poly.outer().push_back(p3); + poly.outer().push_back(p1); + polys.push_back(poly); + const auto all_points_in_cloud = + extractObstaclePointsWithinPolygon(filtered_point_cloud, polys); + EXPECT_FALSE(all_points_in_cloud.empty()); + EXPECT_EQ(all_points_in_cloud.size(), filtered_point_cloud.size()); + } + + sensor_msgs::msg::PointCloud2 ros_pointcloud; + pcl::toROSMsg(point_cloud, ros_pointcloud); + + { + auto filtered_point_cloud = applyVoxelGridFilter(ros_pointcloud); + EXPECT_FALSE(filtered_point_cloud.empty()); + EXPECT_TRUE(filtered_point_cloud.size() < point_cloud.size()); + const bool points_have_no_height = std::all_of( + filtered_point_cloud.begin(), filtered_point_cloud.end(), + [](const auto & p) { return std::abs(p.z) < std::numeric_limits::epsilon(); }); + EXPECT_TRUE(points_have_no_height); + } +} + +TEST_F(TestDynamicObstacleMethods, testGroupPointsWithNearestSegmentIndex) +{ + constexpr size_t n_points{10}; + constexpr double points_resolution{0.025}; + + pcl::PointCloud point_cloud = generate_pointcloud(n_points, points_resolution); + constexpr size_t n_path_points{10}; + PathPointsWithLaneId path; + PathPointWithLaneId base_point; + for (size_t i = 0; i < n_path_points; ++i) { + const PathPointWithLaneId p = createExtendPathPoint(static_cast(i), base_point); + path.push_back(p); + } + const auto grouped_points = groupPointsWithNearestSegmentIndex(point_cloud, path); + EXPECT_FALSE(grouped_points.empty()); + EXPECT_EQ(grouped_points.size(), path.size()); + // first point in path is the closest to all points + EXPECT_EQ(grouped_points.at(0).size(), point_cloud.size()); +} + +TEST_F(TestDynamicObstacleMethods, testCalculateLateralNearestPoint) +{ + constexpr size_t n_points{10}; + constexpr double points_resolution{1.0}; + + pcl::PointCloud point_cloud = generate_pointcloud(n_points, points_resolution); + geometry_msgs::msg::Pose base_pose; + base_pose.position.y = 10.0; + auto nearest_point = calculateLateralNearestPoint(point_cloud, base_pose); + EXPECT_DOUBLE_EQ(nearest_point.y, (n_points - 1) * points_resolution); + + PathPointsWithLaneId path; + PathPointWithLaneId base_point; + constexpr size_t n_path_points{10}; + for (size_t i = 0; i < n_path_points; ++i) { + const PathPointWithLaneId p = createExtendPathPoint(static_cast(i), base_point); + path.push_back(p); + } + + const auto grouped_points = groupPointsWithNearestSegmentIndex(point_cloud, path); + auto lateral_nearest_points = selectLateralNearestPoints(grouped_points, path); + EXPECT_FALSE(grouped_points.empty()); + EXPECT_EQ(grouped_points.size(), path.size()); + EXPECT_TRUE(lateral_nearest_points.size() <= n_path_points); + for (size_t i = 0; i < lateral_nearest_points.size(); ++i) { + const auto p = path.at(i); + const auto curr_nearest_point = lateral_nearest_points.at(i); + auto deviation = std::abs(autoware::universe_utils::calcLateralDeviation( + p.point.pose, + autoware::universe_utils::createPoint(curr_nearest_point.x, curr_nearest_point.y, 0))); + EXPECT_DOUBLE_EQ(deviation, 0.0); + } + + constexpr double interval{1.0}; + const auto path_with_lane_id = + autoware::test_utils::generateTrajectory(n_path_points, interval); + { + const auto interp_lateral_nearest_points = + extractLateralNearestPoints(point_cloud, path_with_lane_id, interval / 4.0); + EXPECT_EQ(interp_lateral_nearest_points.size(), path_with_lane_id.points.size()); + } + + { + const auto interp_lateral_nearest_points = + extractLateralNearestPoints(point_cloud, path_with_lane_id, interval * 2.0); + EXPECT_EQ(interp_lateral_nearest_points.size(), path_with_lane_id.points.size() / 2); + } +} + +TEST_F(TestDynamicObstacleMethods, testConcatPointCloud) +{ + constexpr size_t n_points{10}; + constexpr double points_resolution{0.025}; + + pcl::PointCloud point_cloud_1 = generate_pointcloud(n_points, points_resolution); + pcl::PointCloud point_cloud_2 = + generate_pointcloud(n_points * 2, points_resolution * 2.0); + auto point_cloud_concat = concatPointCloud(point_cloud_1, point_cloud_2); + // the pcl method used by this function generates a pointcloud that has a way bigger size than + // just the sum of both point clouds + EXPECT_TRUE(point_cloud_concat.data.size() >= point_cloud_1.size() + point_cloud_2.size()); + + Eigen::Matrix3f R; + R = Eigen::Matrix3f::Identity(); + Eigen::Vector3f T; + T.setOnes(); + Eigen::Matrix4f transform; // Your Transformation Matrix + transform.setIdentity(); // Set to Identity to make bottom row of Matrix 0,0,0,1 + transform.block<3, 3>(0, 0) = R; + transform.block<3, 1>(0, 3) = T; + + Eigen::Affine3f m; + m.matrix() = transform; + + PointCloud2 ros_pointcloud; + pcl::toROSMsg(point_cloud_1, ros_pointcloud); + + auto transformed_pointcloud = transformPointCloud(ros_pointcloud, m); + EXPECT_TRUE(transformed_pointcloud.at(0).x > T.x() - std::numeric_limits::epsilon()); + EXPECT_TRUE(transformed_pointcloud.at(0).y > T.y() - std::numeric_limits::epsilon()); + EXPECT_TRUE(transformed_pointcloud.at(0).z > T.z() - std::numeric_limits::epsilon()); +} + +TEST_F(TestDynamicObstacleMethods, testCalculateMinAndMaxVelFromCovariance) +{ + geometry_msgs::msg::TwistWithCovariance twist; + twist.covariance[0] = 1.0; + twist.covariance[7] = 1.0; + twist.twist.linear.x = 1.0; + twist.twist.linear.y = 1.0; + + constexpr double std_dev_multiplier{1.0}; + DynamicObstacle dynamic_obstacle; + calculateMinAndMaxVelFromCovariance(twist, std_dev_multiplier, dynamic_obstacle); + EXPECT_TRUE(std::abs(dynamic_obstacle.max_velocity_mps - std::hypot(2.0, 2.0)) < 1e-3); + EXPECT_DOUBLE_EQ(dynamic_obstacle.min_velocity_mps, std::hypot(0.0, 0.0)); +} + +TEST_F(TestDynamicObstacleMethods, testCreatePathToPredictionTime) +{ + autoware_perception_msgs::msg::PredictedPath predicted_path; + constexpr double prediction_time{5.0}; + predicted_path.time_step = rclcpp::Duration(0.0, 100000000.0); + + geometry_msgs::msg::Pose initial_pose; + + constexpr double max_velocity_mps = 1.0; + constexpr double max_prediction_time = 2.0 * prediction_time; + const double time_step = convertDurationToDouble(predicted_path.time_step); + + const auto traj = + createPredictedPath(initial_pose, time_step, max_velocity_mps, max_prediction_time); + predicted_path.path = traj; + + { + auto path_to_prediction_time = createPathToPredictionTime(predicted_path, 0.0); + EXPECT_EQ(0, path_to_prediction_time.size()); + } + + { + auto path_to_prediction_time = createPathToPredictionTime(predicted_path, prediction_time); + EXPECT_EQ(predicted_path.path.size() / 2, path_to_prediction_time.size()); + EXPECT_TRUE( + std::abs(path_to_prediction_time.back().position.x - prediction_time * max_velocity_mps) < + time_step * max_velocity_mps + std::numeric_limits::epsilon()); + } +} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_path_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_path_utils.cpp new file mode 100644 index 0000000000000..eb8502f043b22 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_path_utils.cpp @@ -0,0 +1,71 @@ +// 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 "path_utils.hpp" + +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include +#include + +using autoware::behavior_velocity_planner::run_out_utils::findLongitudinalNearestPoint; +using geometry_msgs::msg::Point; +using tier4_planning_msgs::msg::PathPointWithLaneId; +using tier4_planning_msgs::msg::PathWithLaneId; + +class TestPathUtils : public ::testing::Test +{ + void SetUp() override {} +}; + +TEST_F(TestPathUtils, testFindLongitudinalNearestPoint) +{ + const auto path = + autoware::test_utils::generateTrajectory(10, 1.0, 1.0, 0.0, 0.0); + const auto p_src = path.points.front(); + const auto p_dst = path.points.back(); + const auto p_med = path.points.at(path.points.size() / 2); + + const auto geom_p_src = autoware::universe_utils::createPoint( + p_src.point.pose.position.x, p_src.point.pose.position.y, p_src.point.pose.position.z); + const auto geom_p_dst = autoware::universe_utils::createPoint( + p_dst.point.pose.position.x, p_dst.point.pose.position.y, p_dst.point.pose.position.z); + const auto geom_p_med = autoware::universe_utils::createPoint( + p_med.point.pose.position.x, p_med.point.pose.position.y, p_med.point.pose.position.z); + std::vector dst_points{geom_p_src, geom_p_dst, geom_p_med}; + const auto closest_point_src = findLongitudinalNearestPoint(path.points, geom_p_src, dst_points); + const auto closest_point_dst = findLongitudinalNearestPoint(path.points, geom_p_dst, dst_points); + const auto closest_point_med = findLongitudinalNearestPoint(path.points, geom_p_med, dst_points); + + EXPECT_DOUBLE_EQ( + autoware::universe_utils::calcDistance3d(closest_point_src, geom_p_src), + autoware::universe_utils::calcDistance3d(geom_p_src, geom_p_src)); + EXPECT_DOUBLE_EQ( + autoware::universe_utils::calcDistance3d(closest_point_dst, geom_p_dst), + autoware::universe_utils::calcDistance3d(geom_p_src, geom_p_dst)); + EXPECT_DOUBLE_EQ( + autoware::universe_utils::calcDistance3d(closest_point_med, geom_p_med), + autoware::universe_utils::calcDistance3d(geom_p_src, geom_p_med)); +} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_state_machine.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_state_machine.cpp new file mode 100644 index 0000000000000..d39436baa7dea --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_state_machine.cpp @@ -0,0 +1,107 @@ +// 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 "dynamic_obstacle.hpp" +#include "state_machine.hpp" +#include "utils.hpp" + +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include +#include +#include + +using autoware::behavior_velocity_planner::DynamicObstacle; +using autoware::behavior_velocity_planner::run_out_utils::StateMachine; +using autoware::behavior_velocity_planner::run_out_utils::StateParam; + +using geometry_msgs::msg::Point; +using tier4_planning_msgs::msg::PathPointWithLaneId; +using tier4_planning_msgs::msg::PathWithLaneId; + +class TestStateMachine : public ::testing::Test +{ + void SetUp() override + { + StateParam state_params; + state_params.stop_thresh = stop_thresh_; + state_params.stop_time_thresh = stop_time_thresh_; + state_params.disable_approach_dist = disable_approach_dist_; + state_params.keep_approach_duration = keep_approach_duration_; + state_machine_ptr_ = std::make_shared(state_params); + } + +public: + std::shared_ptr state_machine_ptr_; + float stop_thresh_{2.0}; + float stop_time_thresh_{1.0}; + float keep_approach_duration_{1.0}; + float disable_approach_dist_{1.0}; +}; + +TEST_F(TestStateMachine, testToString) +{ + using State = autoware::behavior_velocity_planner::run_out_utils::StateMachine::State; + State state = state_machine_ptr_->getCurrentState(); + + auto state_string = state_machine_ptr_->toString(state); + EXPECT_EQ(state_string, "GO"); + + state = State::STOP; + state_string = state_machine_ptr_->toString(state); + EXPECT_EQ(state_string, "STOP"); + + state = State::APPROACH; + state_string = state_machine_ptr_->toString(state); + EXPECT_EQ(state_string, "APPROACH"); + + state = State::UNKNOWN; + state_string = state_machine_ptr_->toString(state); + EXPECT_EQ(state_string, "UNKNOWN"); +} + +TEST_F(TestStateMachine, testUpdateState) +{ + rclcpp::init(0, nullptr); + using State = autoware::behavior_velocity_planner::run_out_utils::StateMachine::State; + using StateInput = autoware::behavior_velocity_planner::run_out_utils::StateMachine::StateInput; + constexpr float dist_to_collision{10.0}; + StateInput state_input{stop_thresh_ / 2.0, dist_to_collision, {}}; + state_input.current_obstacle = DynamicObstacle(); + rclcpp::Clock clock(RCL_ROS_TIME); + + EXPECT_TRUE(state_machine_ptr_->getCurrentState() == State::GO); + + // current velocity < stop_threshold. GO -> STOP + state_machine_ptr_->updateState(state_input, clock); + EXPECT_TRUE(state_machine_ptr_->getCurrentState() == State::STOP); + + // if STOP state continues for a certain time, transit to APPROACH state + const int sleep_time = static_cast(stop_time_thresh_) + 1; + std::this_thread::sleep_for(std::chrono::seconds(sleep_time)); + state_machine_ptr_->updateState(state_input, clock); + EXPECT_TRUE(state_machine_ptr_->getCurrentState() == State::APPROACH); + rclcpp::shutdown(); +} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_utils.cpp new file mode 100644 index 0000000000000..c523dd0a53a71 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/tests/test_utils.cpp @@ -0,0 +1,302 @@ +// 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 "dynamic_obstacle.hpp" +#include "path_utils.hpp" +#include "utils.hpp" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +using autoware::behavior_velocity_planner::DynamicObstacle; +using autoware::behavior_velocity_planner::run_out_utils::createBoostPolyFromMsg; +using autoware::behavior_velocity_planner::run_out_utils::createExtendPathPoint; +using autoware::behavior_velocity_planner::run_out_utils::decimatePathPoints; +using autoware::behavior_velocity_planner::run_out_utils::DetectionMethod; +using autoware::behavior_velocity_planner::run_out_utils::findFirstStopPointIdx; +using autoware::behavior_velocity_planner::run_out_utils::findLateralSameSidePoints; +using autoware::behavior_velocity_planner::run_out_utils::getHighestConfidencePath; +using autoware::behavior_velocity_planner::run_out_utils::getHighestProbLabel; +using autoware::behavior_velocity_planner::run_out_utils::insertPathVelocityFromIndex; +using autoware::behavior_velocity_planner::run_out_utils::insertPathVelocityFromIndexLimited; +using autoware::behavior_velocity_planner::run_out_utils::isSamePoint; +using autoware::behavior_velocity_planner::run_out_utils::lerpByPose; +using autoware::behavior_velocity_planner::run_out_utils::pathIntersectsEgoCutLine; +using autoware::behavior_velocity_planner::run_out_utils::PathPointsWithLaneId; +using autoware::behavior_velocity_planner::run_out_utils::PredictedPath; +using autoware::behavior_velocity_planner::run_out_utils::toEnum; +using autoware::behavior_velocity_planner::run_out_utils::trimPathFromSelfPose; + +using autoware_perception_msgs::msg::ObjectClassification; +using geometry_msgs::msg::Point; +using tier4_planning_msgs::msg::PathPointWithLaneId; +using tier4_planning_msgs::msg::PathWithLaneId; + +class TestRunOutUtils : public ::testing::Test +{ + void SetUp() override {} +}; + +TEST_F(TestRunOutUtils, testFindLongitudinalNearestPoint) +{ + std::vector poly; + poly.push_back(autoware::universe_utils::createPoint(0.0, 1.0, 0.0)); + poly.push_back(autoware::universe_utils::createPoint(0.0, -1.0, 0.0)); + poly.push_back(autoware::universe_utils::createPoint(1.0, 1.0, 0.0)); + poly.push_back(autoware::universe_utils::createPoint(1.0, 0.0, 0.0)); + + const auto boost_poly = createBoostPolyFromMsg(poly); + EXPECT_FALSE(boost_poly.outer().empty()); + EXPECT_EQ(boost_poly.outer().size(), poly.size() + 1); +} + +TEST_F(TestRunOutUtils, testGetHighestProbLabel) +{ + ObjectClassification classification_1; + classification_1.label = ObjectClassification::BICYCLE; + classification_1.probability = 0.7; + + ObjectClassification classification_2; + classification_2.label = ObjectClassification::MOTORCYCLE; + classification_2.probability = 0.1; + + ObjectClassification classification_3; + classification_3.label = ObjectClassification::TRUCK; + classification_3.probability = 0.2; + + std::vector classifications{ + classification_1, classification_2, classification_3}; + const auto classification = getHighestProbLabel(classifications); + + EXPECT_EQ(classification, classification_1.label); +} + +TEST_F(TestRunOutUtils, testGetHighestConfidencePath) +{ + std::vector predicted_paths{}; + const auto empty_path = getHighestConfidencePath(predicted_paths); + EXPECT_TRUE(empty_path.empty()); + geometry_msgs::msg::Pose p1; + p1.position.x = 1.0; + + geometry_msgs::msg::Pose p2; + p2.position.x = 2.0; + + PredictedPath predicted_path_1{}; + predicted_path_1.path = {p1}; + predicted_path_1.confidence = 0.85; + + PredictedPath predicted_path_2{}; + predicted_path_2.path = {p2}; + predicted_path_2.confidence = 0.15; + + predicted_paths.push_back(predicted_path_1); + predicted_paths.push_back(predicted_path_2); + + const auto high_confidence_path = getHighestConfidencePath(predicted_paths); + const auto path_point = high_confidence_path.front(); + EXPECT_TRUE(isSamePoint(path_point.position, p1.position)); +} + +TEST_F(TestRunOutUtils, testLerpByPose) +{ + geometry_msgs::msg::Pose p1; + p1.position.x = 1.0; + geometry_msgs::msg::Pose p2; + p2.position.x = 2.0; + const auto p3 = lerpByPose(p1, p2, 0.5); + EXPECT_DOUBLE_EQ(1.5, p3.position.x); +} + +TEST_F(TestRunOutUtils, testFindLateralSameSidePoints) +{ + std::vector points; + for (size_t i = 0; i < 10; ++i) { + geometry_msgs::msg::Point p; + p.x = static_cast(i); + p.y = 0.0; + points.push_back(p); + } + + { + geometry_msgs::msg::Pose base_pose; + base_pose.position.x = 1.0; + base_pose.position.y = -1.0; + + geometry_msgs::msg::Point target_pose; + target_pose.x = 2.0; + target_pose.y = 2.0; + const auto same_points = findLateralSameSidePoints(points, base_pose, target_pose); + EXPECT_EQ(same_points.size(), points.size()); + } + + { + geometry_msgs::msg::Pose base_pose; + base_pose.position.x = 1.0; + base_pose.position.y = 1.0; + + geometry_msgs::msg::Point target_pose; + target_pose.x = 2.0; + target_pose.y = 2.0; + + const auto same_points = findLateralSameSidePoints(points, base_pose, target_pose); + EXPECT_FALSE(same_points.empty()); + } +} + +TEST_F(TestRunOutUtils, testInsertPathVelocity) +{ + constexpr double path_velocity = 2.0; + constexpr size_t n_path_points = 100; + + PathPointWithLaneId p; + p.point.longitudinal_velocity_mps = path_velocity; + PathPointsWithLaneId path(n_path_points, p); + + const size_t middle_index = path.size() / 2; + + constexpr double high_velocity = 2.0 * path_velocity; + insertPathVelocityFromIndexLimited(middle_index, high_velocity, path); + const auto middle_itr = path.begin() + path.size() / 2; + const bool is_velocity_not_modified = + std::all_of(middle_itr, path.end(), [path_velocity](const auto & v) { + return std::abs(v.point.longitudinal_velocity_mps - path_velocity) < + std::numeric_limits::epsilon(); + }); + EXPECT_TRUE(is_velocity_not_modified); + + constexpr double low_velocity = 0.5 * path_velocity; + insertPathVelocityFromIndexLimited(middle_index, low_velocity, path); + const bool is_velocity_modified = + std::all_of(middle_itr, path.end(), [low_velocity](const auto & v) { + return std::abs(v.point.longitudinal_velocity_mps - low_velocity) < + std::numeric_limits::epsilon(); + }); + EXPECT_TRUE(is_velocity_modified); + + insertPathVelocityFromIndex(0, high_velocity, path); + const bool all_velocities_modified = + std::all_of(path.begin(), path.end(), [high_velocity](const auto & v) { + return std::abs(v.point.longitudinal_velocity_mps - high_velocity) < + std::numeric_limits::epsilon(); + }); + EXPECT_TRUE(all_velocities_modified); + + auto first_stop_point = findFirstStopPointIdx(path); + EXPECT_FALSE(first_stop_point.has_value()); + insertPathVelocityFromIndex(middle_index, 0.0, path); + first_stop_point = findFirstStopPointIdx(path); + EXPECT_TRUE(first_stop_point.has_value()); + EXPECT_EQ(middle_index, first_stop_point.value()); +} + +TEST_F(TestRunOutUtils, testPathIntersectsEgoCutLine) +{ + std::vector poses; + geometry_msgs::msg::Pose ego_pose; + constexpr double half_line_length = 2.0; + std::vector ego_cut_line; + EXPECT_FALSE(pathIntersectsEgoCutLine(poses, ego_pose, half_line_length, ego_cut_line)); + for (size_t i = 0; i < 10; ++i) { + geometry_msgs::msg::Pose p; + p.position.x = static_cast(i) - 5.0; + p.position.y = 0.5; + poses.push_back(p); + } + + EXPECT_TRUE(pathIntersectsEgoCutLine(poses, ego_pose, half_line_length, ego_cut_line)); + ego_pose.position.y = 3.0; + EXPECT_FALSE(pathIntersectsEgoCutLine(poses, ego_pose, half_line_length, ego_cut_line)); +} + +TEST_F(TestRunOutUtils, testExcludeObstaclesOutSideOfLine) +{ + constexpr size_t n_path_points{100}; + + PathPointsWithLaneId path; + + PathPointWithLaneId base_point; + + for (size_t i = 0; i < n_path_points; ++i) { + const PathPointWithLaneId p = createExtendPathPoint(static_cast(i) / 10.0, base_point); + path.push_back(p); + } + + path = decimatePathPoints(path, 1.0); + EXPECT_EQ(path.size(), n_path_points / 10); + + lanelet::BasicPolygon2d partition; + partition.emplace_back(1.0, 1.0); + partition.emplace_back(2.0, 1.0); + partition.emplace_back(3.0, 1.0); + partition.emplace_back(4.0, 1.0); + + constexpr double long_position{2.0}; + constexpr double lat_position_of_excluded_obstacle{2.0}; + constexpr double lat_position_of_included_obstacle{-2.0}; + + DynamicObstacle obstacle_1; + obstacle_1.pose.position.x = long_position; + obstacle_1.pose.position.y = lat_position_of_included_obstacle; + + DynamicObstacle obstacle_2; + obstacle_2.pose.position.x = long_position; + obstacle_2.pose.position.y = lat_position_of_excluded_obstacle; + std::vector obstacles{obstacle_1, obstacle_2}; + + const auto filtered_obstacles = excludeObstaclesOutSideOfLine(obstacles, path, partition); + + EXPECT_EQ(filtered_obstacles.size(), 1); + EXPECT_DOUBLE_EQ(filtered_obstacles.front().pose.position.y, lat_position_of_included_obstacle); +} + +TEST_F(TestRunOutUtils, testTrimPathFromSelfPose) +{ + constexpr double point_interval{1e-2}; + const auto path = + autoware::test_utils::generateTrajectory(1000, point_interval, 1.0, 0.0, 0.0); + + geometry_msgs::msg::Pose self_pose; + constexpr double trim_distance{10.0}; + + const auto trimmed_path = trimPathFromSelfPose(path, self_pose, trim_distance); + const auto path_length = autoware::motion_utils::calcArcLength(path.points); + EXPECT_TRUE( + path_length - trim_distance < point_interval + std::numeric_limits::epsilon()); +} + +TEST_F(TestRunOutUtils, testToEnum) +{ + EXPECT_EQ(toEnum("Object"), DetectionMethod::Object); + EXPECT_EQ(toEnum("ObjectWithoutPath"), DetectionMethod::ObjectWithoutPath); + EXPECT_EQ(toEnum("Points"), DetectionMethod::Points); + EXPECT_EQ(toEnum("Autoware"), DetectionMethod::Unknown); +} From 827a5d9147bb05b38c0916700b291c911966f6b0 Mon Sep 17 00:00:00 2001 From: TetsuKawa <70682030+TetsuKawa@users.noreply.github.com> Date: Thu, 14 Nov 2024 19:21:58 +0900 Subject: [PATCH 006/273] feat(hazard_status_converter): hazard status converter subscribe emergency holding (#9287) * feat: add subscriber for emergency_holding Signed-off-by: TetsuKawa * modify: fix value name Signed-off-by: TetsuKawa * style(pre-commit): autofix Signed-off-by: TetsuKawa * feat: add const to is_emergency_holding Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> Signed-off-by: TetsuKawa --------- Signed-off-by: TetsuKawa Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> --- .../launch/hazard_status_converter.launch.xml | 1 + system/hazard_status_converter/package.xml | 1 + system/hazard_status_converter/src/converter.cpp | 5 ++++- system/hazard_status_converter/src/converter.hpp | 5 +++++ 4 files changed, 11 insertions(+), 1 deletion(-) diff --git a/system/hazard_status_converter/launch/hazard_status_converter.launch.xml b/system/hazard_status_converter/launch/hazard_status_converter.launch.xml index f3b07bfa94834..84318a921d4ce 100644 --- a/system/hazard_status_converter/launch/hazard_status_converter.launch.xml +++ b/system/hazard_status_converter/launch/hazard_status_converter.launch.xml @@ -2,5 +2,6 @@ + diff --git a/system/hazard_status_converter/package.xml b/system/hazard_status_converter/package.xml index ec54b4c003080..7d154abb7b26c 100644 --- a/system/hazard_status_converter/package.xml +++ b/system/hazard_status_converter/package.xml @@ -12,6 +12,7 @@ autoware_adapi_v1_msgs autoware_system_msgs + autoware_universe_utils diagnostic_graph_utils diagnostic_msgs rclcpp diff --git a/system/hazard_status_converter/src/converter.cpp b/system/hazard_status_converter/src/converter.cpp index e8213b441bb33..d92af2186f415 100644 --- a/system/hazard_status_converter/src/converter.cpp +++ b/system/hazard_status_converter/src/converter.cpp @@ -117,7 +117,10 @@ void Converter::on_update(DiagGraph::ConstSharedPtr graph) hazard.stamp = graph->updated_stamp(); hazard.status.level = get_system_level(hazard.status); hazard.status.emergency = hazard.status.level == HazardStatus::SINGLE_POINT_FAULT; - hazard.status.emergency_holding = false; + + const auto is_emergency_holding = sub_emergency_holding_.takeData(); + hazard.status.emergency_holding = + is_emergency_holding == nullptr ? false : is_emergency_holding->is_holding; pub_hazard_->publish(hazard); } diff --git a/system/hazard_status_converter/src/converter.hpp b/system/hazard_status_converter/src/converter.hpp index 442eedf588429..8011b911f3d42 100644 --- a/system/hazard_status_converter/src/converter.hpp +++ b/system/hazard_status_converter/src/converter.hpp @@ -15,10 +15,12 @@ #ifndef CONVERTER_HPP_ #define CONVERTER_HPP_ +#include #include #include #include +#include #include @@ -38,6 +40,9 @@ class Converter : public rclcpp::Node void on_update(DiagGraph::ConstSharedPtr graph); diagnostic_graph_utils::DiagGraphSubscription sub_graph_; rclcpp::Publisher::SharedPtr pub_hazard_; + autoware::universe_utils::InterProcessPollingSubscriber< + tier4_system_msgs::msg::EmergencyHoldingState> + sub_emergency_holding_{this, "~/input/emergency_holding"}; DiagUnit * auto_mode_root_; std::unordered_set auto_mode_tree_; From c6c3b1c6e6e2dc3a1f8a84a9d72dce8a171fece7 Mon Sep 17 00:00:00 2001 From: TetsuKawa <70682030+TetsuKawa@users.noreply.github.com> Date: Thu, 14 Nov 2024 19:22:29 +0900 Subject: [PATCH 007/273] feat(mrm_handler): mrm handler publish emergecy holding (#9285) * feat: add publisher for emrgency holding Signed-off-by: TetsuKawa * modify: fix msg element Signed-off-by: TetsuKawa * style(pre-commit): autofix --------- Signed-off-by: TetsuKawa Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/mrm_handler/mrm_handler_core.hpp | 5 +++++ system/mrm_handler/launch/mrm_handler.launch.xml | 2 ++ .../mrm_handler/src/mrm_handler/mrm_handler_core.cpp | 11 +++++++++++ 3 files changed, 18 insertions(+) diff --git a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp index f73d0df4153ce..b292ab1d874d3 100644 --- a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp +++ b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include #include @@ -109,6 +110,10 @@ class MrmHandler : public rclcpp::Node autoware_adapi_v1_msgs::msg::MrmState mrm_state_; void publishMrmState(); + rclcpp::Publisher::SharedPtr + pub_emergency_holding_; + void publishEmergencyHolding(); + // Clients rclcpp::CallbackGroup::SharedPtr client_mrm_pull_over_group_; rclcpp::Client::SharedPtr client_mrm_pull_over_; diff --git a/system/mrm_handler/launch/mrm_handler.launch.xml b/system/mrm_handler/launch/mrm_handler.launch.xml index c99b22e10ad77..51a22cf92bebc 100644 --- a/system/mrm_handler/launch/mrm_handler.launch.xml +++ b/system/mrm_handler/launch/mrm_handler.launch.xml @@ -12,6 +12,7 @@ + @@ -32,6 +33,7 @@ + diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp index 0fc0cb29ecf21..4022bdaadebef 100644 --- a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -49,6 +49,8 @@ MrmHandler::MrmHandler(const rclcpp::NodeOptions & options) : Node("mrm_handler" create_publisher("~/output/gear", rclcpp::QoS{1}); pub_mrm_state_ = create_publisher("~/output/mrm/state", rclcpp::QoS{1}); + pub_emergency_holding_ = create_publisher( + "~/output/emergency_holding", rclcpp::QoS{1}); // Clients client_mrm_pull_over_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); @@ -153,6 +155,14 @@ void MrmHandler::publishMrmState() pub_mrm_state_->publish(mrm_state_); } +void MrmHandler::publishEmergencyHolding() +{ + tier4_system_msgs::msg::EmergencyHoldingState msg; + msg.stamp = this->now(); + msg.is_holding = is_emergency_holding_; + pub_emergency_holding_->publish(msg); +} + void MrmHandler::operateMrm() { using autoware_adapi_v1_msgs::msg::MrmState; @@ -352,6 +362,7 @@ void MrmHandler::onTimer() publishMrmState(); publishHazardCmd(); publishGearCmd(); + publishEmergencyHolding(); } void MrmHandler::transitionTo(const int new_state) From b4603fd06fa2b81c90dece1385652cce2d4cd438 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 14 Nov 2024 20:39:29 +0900 Subject: [PATCH 008/273] feat(trajectory_follower): publsih control horzion (#8977) * feat(trajectory_follower): publsih control horzion Signed-off-by: kosuke55 * fix typo Signed-off-by: kosuke55 * rename functions and minor refactor Signed-off-by: kosuke55 * add option to enable horizon pub Signed-off-by: kosuke55 * add tests for horizon Signed-off-by: kosuke55 * update docs Signed-off-by: kosuke55 * rename to ~/debug/control_cmd_horizon Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../autoware/mpc_lateral_controller/mpc.hpp | 5 +- .../mpc_lateral_controller.hpp | 9 ++ .../src/mpc.cpp | 16 ++- .../src/mpc_lateral_controller.cpp | 25 +++- .../test/test_mpc.cpp | 72 +++++++++--- .../src/pid_longitudinal_controller.cpp | 8 +- .../control_horizon.hpp | 42 +++++++ .../lateral_controller_base.hpp | 5 +- .../longitudinal_controller_base.hpp | 5 +- .../README.md | 2 + .../controller_node.hpp | 21 ++++ .../src/controller_node.cpp | 110 ++++++++++++++++++ 12 files changed, 298 insertions(+), 22 deletions(-) create mode 100644 control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/control_horizon.hpp diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp index 36a79cc95728e..0e4691822326f 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp @@ -20,6 +20,7 @@ #include "autoware/mpc_lateral_controller/qp_solver/qp_solver_interface.hpp" #include "autoware/mpc_lateral_controller/steering_predictor.hpp" #include "autoware/mpc_lateral_controller/vehicle_model/vehicle_model_interface.hpp" +#include "autoware/trajectory_follower_base/control_horizon.hpp" #include "rclcpp/rclcpp.hpp" #include "autoware_control_msgs/msg/lateral.hpp" @@ -38,6 +39,7 @@ namespace autoware::motion::control::mpc_lateral_controller { +using autoware::motion::control::trajectory_follower::LateralHorizon; using autoware_control_msgs::msg::Lateral; using autoware_planning_msgs::msg::Trajectory; using autoware_vehicle_msgs::msg::SteeringReport; @@ -450,7 +452,8 @@ class MPC */ bool calculateMPC( const SteeringReport & current_steer, const Odometry & current_kinematics, Lateral & ctrl_cmd, - Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic); + Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic, + LateralHorizon & ctrl_cmd_horizon); /** * @brief Set the reference trajectory to be followed. diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp index 09399d1fa2dce..aca0f0ccbc814 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -22,6 +22,7 @@ #include "autoware/trajectory_follower_base/lateral_controller_base.hpp" #include "rclcpp/rclcpp.hpp" +#include #include #include "autoware_control_msgs/msg/lateral.hpp" @@ -49,6 +50,7 @@ using autoware_vehicle_msgs::msg::SteeringReport; using nav_msgs::msg::Odometry; using tier4_debug_msgs::msg::Float32MultiArrayStamped; using tier4_debug_msgs::msg::Float32Stamped; +using trajectory_follower::LateralHorizon; class MpcLateralController : public trajectory_follower::LateralControllerBase { @@ -214,6 +216,13 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase */ Lateral createCtrlCmdMsg(const Lateral & ctrl_cmd); + /** + * @brief Create the control command horizon message. + * @param ctrl_cmd_horizon Control command horizon to be created. + * @return Created control command horizon. + */ + LateralHorizon createCtrlCmdHorizonMsg(const LateralHorizon & ctrl_cmd_horizon) const; + /** * @brief Publish the predicted future trajectory. * @param predicted_traj Predicted future trajectory to be published. diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 0f350dc40ad0e..2d2179bb41a84 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -39,7 +39,8 @@ MPC::MPC(rclcpp::Node & node) bool MPC::calculateMPC( const SteeringReport & current_steer, const Odometry & current_kinematics, Lateral & ctrl_cmd, - Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic) + Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic, + LateralHorizon & ctrl_cmd_horizon) { // since the reference trajectory does not take into account the current velocity of the ego // vehicle, it needs to calculate the trajectory velocity considering the longitudinal dynamics. @@ -124,6 +125,19 @@ bool MPC::calculateMPC( diagnostic = generateDiagData(reference_trajectory, mpc_data, mpc_matrix, ctrl_cmd, Uex, current_kinematics); + // create LateralHorizon command + ctrl_cmd_horizon.time_step_ms = prediction_dt * 1000.0; + ctrl_cmd_horizon.controls.clear(); + ctrl_cmd_horizon.controls.push_back(ctrl_cmd); + for (auto it = std::next(Uex.begin()); it != Uex.end(); ++it) { + Lateral lateral{}; + lateral.steering_tire_angle = static_cast(std::clamp(*it, -m_steer_lim, m_steer_lim)); + lateral.steering_tire_rotation_rate = + (lateral.steering_tire_angle - ctrl_cmd_horizon.controls.back().steering_tire_angle) / + m_ctrl_period; + ctrl_cmd_horizon.controls.push_back(lateral); + } + return true; } diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index f4ba74d74f246..7998aafd8cb4f 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -276,8 +276,10 @@ trajectory_follower::LateralOutput MpcLateralController::run( m_is_ctrl_cmd_prev_initialized = true; } + trajectory_follower::LateralHorizon ctrl_cmd_horizon{}; const bool is_mpc_solved = m_mpc->calculateMPC( - m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values); + m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values, + ctrl_cmd_horizon); m_is_mpc_solved = is_mpc_solved; // for diagnostic updater @@ -304,9 +306,13 @@ trajectory_follower::LateralOutput MpcLateralController::run( publishPredictedTraj(predicted_traj); publishDebugValues(debug_values); - const auto createLateralOutput = [this](const auto & cmd, const bool is_mpc_solved) { + const auto createLateralOutput = + [this]( + const auto & cmd, const bool is_mpc_solved, + const auto & cmd_horizon) -> trajectory_follower::LateralOutput { trajectory_follower::LateralOutput output; output.control_cmd = createCtrlCmdMsg(cmd); + output.control_cmd_horizon = createCtrlCmdHorizonMsg(cmd_horizon); // To be sure current steering of the vehicle is desired steering angle, we need to check // following conditions. // 1. At the last loop, mpc should be solved because command should be optimized output. @@ -325,7 +331,7 @@ trajectory_follower::LateralOutput MpcLateralController::run( } // Use previous command value as previous raw steer command m_mpc->m_raw_steer_cmd_prev = m_ctrl_cmd_prev.steering_tire_angle; - return createLateralOutput(m_ctrl_cmd_prev, false); + return createLateralOutput(m_ctrl_cmd_prev, false, ctrl_cmd_horizon); } if (!is_mpc_solved) { @@ -334,7 +340,7 @@ trajectory_follower::LateralOutput MpcLateralController::run( } m_ctrl_cmd_prev = ctrl_cmd; - return createLateralOutput(ctrl_cmd, is_mpc_solved); + return createLateralOutput(ctrl_cmd, is_mpc_solved, ctrl_cmd_horizon); } bool MpcLateralController::isSteerConverged(const Lateral & cmd) const @@ -465,6 +471,17 @@ Lateral MpcLateralController::createCtrlCmdMsg(const Lateral & ctrl_cmd) return out; } +LateralHorizon MpcLateralController::createCtrlCmdHorizonMsg( + const LateralHorizon & ctrl_cmd_horizon) const +{ + auto out = ctrl_cmd_horizon; + const auto now = clock_->now(); + for (auto & cmd : out.controls) { + cmd.stamp = now; + } + return out; +} + void MpcLateralController::publishPredictedTraj(Trajectory & predicted_traj) const { predicted_traj.header.stamp = clock_->now(); diff --git a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp index c4a67552a6083..fe2ca8d451018 100644 --- a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp +++ b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp @@ -21,6 +21,8 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" +#include + #include "autoware_control_msgs/msg/lateral.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" @@ -41,6 +43,7 @@ namespace autoware::motion::control::mpc_lateral_controller { +using autoware::motion::control::trajectory_follower::LateralHorizon; using autoware_control_msgs::msg::Lateral; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -209,10 +212,14 @@ TEST_F(MPCTest, InitializeAndCalculate) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, InitializeAndCalculateRightTurn) @@ -241,10 +248,14 @@ TEST_F(MPCTest, InitializeAndCalculateRightTurn) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_LT(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_LT(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, OsqpCalculate) @@ -268,10 +279,14 @@ TEST_F(MPCTest, OsqpCalculate) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - EXPECT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, OsqpCalculateRightTurn) @@ -296,10 +311,14 @@ TEST_F(MPCTest, OsqpCalculateRightTurn) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_LT(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_LT(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, KinematicsNoDelayCalculate) @@ -326,10 +345,14 @@ TEST_F(MPCTest, KinematicsNoDelayCalculate) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, KinematicsNoDelayCalculateRightTurn) @@ -357,10 +380,14 @@ TEST_F(MPCTest, KinematicsNoDelayCalculateRightTurn) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_LT(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_LT(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, DynamicCalculate) @@ -382,10 +409,14 @@ TEST_F(MPCTest, DynamicCalculate) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, MultiSolveWithBuffer) @@ -406,24 +437,37 @@ TEST_F(MPCTest, MultiSolveWithBuffer) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); + ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); + EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); + EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); } TEST_F(MPCTest, FailureCases) @@ -446,11 +490,13 @@ TEST_F(MPCTest, FailureCases) Lateral ctrl_cmd; Trajectory pred_traj; Float32MultiArrayStamped diag; + LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_far, default_velocity); - EXPECT_FALSE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag)); + EXPECT_FALSE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); // Calculate MPC with a fast velocity to make the prediction go further than the reference path EXPECT_FALSE(mpc->calculateMPC( - neutral_steer, makeOdometry(pose_far, default_velocity + 10.0), ctrl_cmd, pred_traj, diag)); + neutral_steer, makeOdometry(pose_far, default_velocity + 10.0), ctrl_cmd, pred_traj, diag, + ctrl_cmd_horizon)); } } // namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index e3cdc4505c037..9bc9a5cd59ac3 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -433,6 +433,8 @@ trajectory_follower::LongitudinalOutput PidLongitudinalController::run( publishDebugData(raw_ctrl_cmd, control_data); // publish debug data trajectory_follower::LongitudinalOutput output; output.control_cmd = cmd_msg; + output.control_cmd_horizon.controls.push_back(cmd_msg); + output.control_cmd_horizon.time_step_ms = 0.0; return output; } @@ -442,11 +444,15 @@ trajectory_follower::LongitudinalOutput PidLongitudinalController::run( // calculate control command const Motion ctrl_cmd = calcCtrlCmd(control_data); - // publish control command + // create control command const auto cmd_msg = createCtrlCmdMsg(ctrl_cmd, control_data.current_motion.vel); trajectory_follower::LongitudinalOutput output; output.control_cmd = cmd_msg; + // create control command horizon + output.control_cmd_horizon.controls.push_back(cmd_msg); + output.control_cmd_horizon.time_step_ms = 0.0; + // publish debug data publishDebugData(ctrl_cmd, control_data); diff --git a/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/control_horizon.hpp b/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/control_horizon.hpp new file mode 100644 index 0000000000000..980568cc73dc6 --- /dev/null +++ b/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/control_horizon.hpp @@ -0,0 +1,42 @@ +// Copyright 2024 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. + +#ifndef AUTOWARE__TRAJECTORY_FOLLOWER_BASE__CONTROL_HORIZON_HPP_ +#define AUTOWARE__TRAJECTORY_FOLLOWER_BASE__CONTROL_HORIZON_HPP_ + +#include "autoware_control_msgs/msg/lateral.hpp" +#include "autoware_control_msgs/msg/longitudinal.hpp" + +#include + +namespace autoware::motion::control::trajectory_follower +{ + +using autoware_control_msgs::msg::Lateral; +using autoware_control_msgs::msg::Longitudinal; + +struct LateralHorizon +{ + double time_step_ms; + std::vector controls; +}; + +struct LongitudinalHorizon +{ + double time_step_ms; + std::vector controls; +}; + +} // namespace autoware::motion::control::trajectory_follower +#endif // AUTOWARE__TRAJECTORY_FOLLOWER_BASE__CONTROL_HORIZON_HPP_ diff --git a/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/lateral_controller_base.hpp b/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/lateral_controller_base.hpp index 891b3982ddf49..4a3ddee78f6ad 100644 --- a/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/lateral_controller_base.hpp +++ b/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/lateral_controller_base.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__TRAJECTORY_FOLLOWER_BASE__LATERAL_CONTROLLER_BASE_HPP_ #define AUTOWARE__TRAJECTORY_FOLLOWER_BASE__LATERAL_CONTROLLER_BASE_HPP_ +#include "autoware/trajectory_follower_base/control_horizon.hpp" #include "autoware/trajectory_follower_base/input_data.hpp" #include "autoware/trajectory_follower_base/sync_data.hpp" #include "rclcpp/rclcpp.hpp" @@ -24,9 +25,11 @@ #include namespace autoware::motion::control::trajectory_follower { +using autoware_control_msgs::msg::Lateral; struct LateralOutput { - autoware_control_msgs::msg::Lateral control_cmd; + Lateral control_cmd; + LateralHorizon control_cmd_horizon; LateralSyncData sync_data; }; diff --git a/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/longitudinal_controller_base.hpp b/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/longitudinal_controller_base.hpp index 176141572d6a8..3c440c5a6dfb6 100644 --- a/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/longitudinal_controller_base.hpp +++ b/control/autoware_trajectory_follower_base/include/autoware/trajectory_follower_base/longitudinal_controller_base.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__TRAJECTORY_FOLLOWER_BASE__LONGITUDINAL_CONTROLLER_BASE_HPP_ #define AUTOWARE__TRAJECTORY_FOLLOWER_BASE__LONGITUDINAL_CONTROLLER_BASE_HPP_ +#include "autoware/trajectory_follower_base/control_horizon.hpp" #include "autoware/trajectory_follower_base/input_data.hpp" #include "autoware/trajectory_follower_base/sync_data.hpp" #include "rclcpp/rclcpp.hpp" @@ -25,9 +26,11 @@ namespace autoware::motion::control::trajectory_follower { +using autoware_control_msgs::msg::Longitudinal; struct LongitudinalOutput { - autoware_control_msgs::msg::Longitudinal control_cmd; + Longitudinal control_cmd; + LongitudinalHorizon control_cmd_horizon; LongitudinalSyncData sync_data; }; class LongitudinalControllerBase diff --git a/control/autoware_trajectory_follower_node/README.md b/control/autoware_trajectory_follower_node/README.md index aa692c323f6d0..ac05dd67f18e6 100644 --- a/control/autoware_trajectory_follower_node/README.md +++ b/control/autoware_trajectory_follower_node/README.md @@ -136,6 +136,7 @@ Giving the longitudinal controller information about steer convergence allows it #### Outputs - `autoware_control_msgs/Control`: message containing both lateral and longitudinal commands. +- `autoware_control_msgs/ControlHorizon`: message containing both lateral and longitudinal horizon commands. this is NOT published by default. by using this, the performance of vehicle control may be improved, and by turning the default on, it can be used as an experimental topic. #### Parameter @@ -146,6 +147,7 @@ Giving the longitudinal controller information about steer convergence allows it 2. The last received commands are not older than defined by `timeout_thr_sec`. - `lateral_controller_mode`: `mpc` or `pure_pursuit` - (currently there is only `PID` for longitudinal controller) +- `enable_control_cmd_horizon_pub`: publish `ControlHorizon` or not (default: false) ## Debugging diff --git a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp index a5f8665328f34..1733b4bcbbb7d 100644 --- a/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp +++ b/control/autoware_trajectory_follower_node/include/autoware/trajectory_follower_node/controller_node.hpp @@ -15,6 +15,7 @@ #ifndef AUTOWARE__TRAJECTORY_FOLLOWER_NODE__CONTROLLER_NODE_HPP_ #define AUTOWARE__TRAJECTORY_FOLLOWER_NODE__CONTROLLER_NODE_HPP_ +#include "autoware/trajectory_follower_base/control_horizon.hpp" #include "autoware/trajectory_follower_base/lateral_controller_base.hpp" #include "autoware/trajectory_follower_base/longitudinal_controller_base.hpp" #include "autoware/trajectory_follower_node/visibility_control.hpp" @@ -33,6 +34,7 @@ #include #include "autoware_control_msgs/msg/control.hpp" +#include "autoware_control_msgs/msg/control_horizon.hpp" #include "autoware_control_msgs/msg/longitudinal.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "geometry_msgs/msg/accel_stamped.hpp" @@ -41,6 +43,7 @@ #include "nav_msgs/msg/odometry.hpp" #include "tf2_msgs/msg/tf_message.hpp" #include "visualization_msgs/msg/marker_array.hpp" +#include #include #include @@ -50,13 +53,16 @@ namespace autoware::motion::control { +using trajectory_follower::LateralHorizon; using trajectory_follower::LateralOutput; +using trajectory_follower::LongitudinalHorizon; using trajectory_follower::LongitudinalOutput; namespace trajectory_follower_node { using autoware::universe_utils::StopWatch; using autoware_adapi_v1_msgs::msg::OperationModeState; +using autoware_control_msgs::msg::ControlHorizon; using tier4_debug_msgs::msg::Float64Stamped; namespace trajectory_follower = ::autoware::motion::control::trajectory_follower; @@ -72,6 +78,7 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node private: rclcpp::TimerBase::SharedPtr timer_control_; double timeout_thr_sec_; + bool enable_control_cmd_horizon_pub_{false}; boost::optional longitudinal_output_{boost::none}; std::shared_ptr diag_updater_ = @@ -104,6 +111,7 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_processing_time_lat_ms_; rclcpp::Publisher::SharedPtr pub_processing_time_lon_ms_; rclcpp::Publisher::SharedPtr debug_marker_pub_; + rclcpp::Publisher::SharedPtr control_cmd_horizon_pub_; autoware_planning_msgs::msg::Trajectory::ConstSharedPtr current_trajectory_ptr_; nav_msgs::msg::Odometry::ConstSharedPtr current_odometry_ptr_; @@ -134,6 +142,19 @@ class TRAJECTORY_FOLLOWER_PUBLIC Controller : public rclcpp::Node void publishDebugMarker( const trajectory_follower::InputData & input_data, const trajectory_follower::LateralOutput & lat_out) const; + /** + * @brief merge lateral and longitudinal horizons + * @details If one of the commands has only one control, repeat the control to match the other + * horizon. If each horizon has different time intervals, resample them to match the size + * with the greatest common divisor. + * @param lateral_horizon lateral horizon + * @param longitudinal_horizon longitudinal horizon + * @param stamp stamp + * @return merged control horizon + */ + static std::optional mergeLatLonHorizon( + const LateralHorizon & lateral_horizon, const LongitudinalHorizon & longitudinal_horizon, + const rclcpp::Time & stamp); std::unique_ptr logger_configure_; diff --git a/control/autoware_trajectory_follower_node/src/controller_node.cpp b/control/autoware_trajectory_follower_node/src/controller_node.cpp index d5167f5096786..7dfbefadca52c 100644 --- a/control/autoware_trajectory_follower_node/src/controller_node.cpp +++ b/control/autoware_trajectory_follower_node/src/controller_node.cpp @@ -19,6 +19,8 @@ #include "autoware/pure_pursuit/autoware_pure_pursuit_lateral_controller.hpp" #include "autoware/universe_utils/ros/marker_helper.hpp" +#include + #include #include #include @@ -26,6 +28,26 @@ #include #include +namespace +{ +template +std::vector resampleHorizonByZeroOrderHold( + const std::vector & original_horizon, const double original_time_step_ms, + const double new_time_step_ms) +{ + std::vector resampled_horizon{}; + const size_t step_factor = static_cast(original_time_step_ms / new_time_step_ms); + const size_t resampled_size = original_horizon.size() * step_factor; + resampled_horizon.reserve(resampled_size); + for (const auto & command : original_horizon) { + for (size_t i = 0; i < step_factor; ++i) { + resampled_horizon.push_back(command); + } + } + return resampled_horizon; +} +} // namespace + namespace autoware::motion::control::trajectory_follower_node { Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("controller", node_options) @@ -34,6 +56,11 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control const double ctrl_period = declare_parameter("ctrl_period"); timeout_thr_sec_ = declare_parameter("timeout_thr_sec"); + // NOTE: It is possible that using control_horizon could be expected to enhance performance, + // but it is not a formal interface topic, only an experimental one. + // So it is disabled by default. + enable_control_cmd_horizon_pub_ = + declare_parameter("enable_control_cmd_horizon_pub", false); const auto lateral_controller_mode = getLateralControllerMode(declare_parameter("lateral_controller_mode")); @@ -74,6 +101,11 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control debug_marker_pub_ = create_publisher("~/output/debug_marker", rclcpp::QoS{1}); + if (enable_control_cmd_horizon_pub_) { + control_cmd_horizon_pub_ = create_publisher( + "~/debug/control_cmd_horizon", 1); + } + // Timer { const auto period_ns = std::chrono::duration_cast( @@ -215,6 +247,15 @@ void Controller::callbackTimerControl() // 6. publish debug published_time_publisher_->publish_if_subscribed(control_cmd_pub_, out.stamp); publishDebugMarker(*input_data, lat_out); + + // 7. publish experimental topic + if (enable_control_cmd_horizon_pub_) { + const auto control_horizon = + mergeLatLonHorizon(lat_out.control_cmd_horizon, lon_out.control_cmd_horizon, this->now()); + if (control_horizon.has_value()) { + control_cmd_horizon_pub_->publish(control_horizon.value()); + } + } } void Controller::publishDebugMarker( @@ -254,6 +295,75 @@ void Controller::publishProcessingTime( pub->publish(msg); } +std::optional Controller::mergeLatLonHorizon( + const LateralHorizon & lateral_horizon, const LongitudinalHorizon & longitudinal_horizon, + const rclcpp::Time & stamp) +{ + if (lateral_horizon.controls.empty() || longitudinal_horizon.controls.empty()) { + return std::nullopt; + } + + autoware_control_msgs::msg::ControlHorizon control_horizon{}; + control_horizon.stamp = stamp; + + // If either of the horizons has only one control, repeat the control to match the other horizon. + if (lateral_horizon.controls.size() == 1) { + control_horizon.time_step_ms = longitudinal_horizon.time_step_ms; + const auto lateral = lateral_horizon.controls.front(); + for (const auto & longitudinal : longitudinal_horizon.controls) { + autoware_control_msgs::msg::Control control; + control.longitudinal = longitudinal; + control.lateral = lateral; + control.stamp = stamp; + control_horizon.controls.push_back(control); + } + return control_horizon; + } + if (longitudinal_horizon.controls.size() == 1) { + control_horizon.time_step_ms = lateral_horizon.time_step_ms; + const auto longitudinal = longitudinal_horizon.controls.front(); + for (const auto & lateral : lateral_horizon.controls) { + autoware_control_msgs::msg::Control control; + control.longitudinal = longitudinal; + control.lateral = lateral; + control.stamp = stamp; + control_horizon.controls.push_back(control); + } + return control_horizon; + } + + // If both horizons have multiple controls, align the time steps and zero-order hold the controls. + // calculate greatest common divisor of time steps + const auto gcd_double = [](const double a, const double b) { + const double precision = 1e9; + const int int_a = static_cast(round(a * precision)); + const int int_b = static_cast(round(b * precision)); + return static_cast(std::gcd(int_a, int_b)) / precision; + }; + const double time_step_ms = + gcd_double(lateral_horizon.time_step_ms, longitudinal_horizon.time_step_ms); + control_horizon.time_step_ms = time_step_ms; + + const auto lateral_controls = resampleHorizonByZeroOrderHold( + lateral_horizon.controls, lateral_horizon.time_step_ms, time_step_ms); + const auto longitudinal_controls = resampleHorizonByZeroOrderHold( + longitudinal_horizon.controls, longitudinal_horizon.time_step_ms, time_step_ms); + + if (lateral_controls.size() != longitudinal_controls.size()) { + return std::nullopt; + } + + const size_t num_steps = lateral_controls.size(); + for (size_t i = 0; i < num_steps; ++i) { + autoware_control_msgs::msg::Control control{}; + control.stamp = stamp; + control.lateral = lateral_controls.at(i); + control.longitudinal = longitudinal_controls.at(i); + control_horizon.controls.push_back(control); + } + return control_horizon; +} + } // namespace autoware::motion::control::trajectory_follower_node #include "rclcpp_components/register_node_macro.hpp" From a59d309b050848a9063b7eaa2b57d1643d9e97f6 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Thu, 14 Nov 2024 12:58:45 +0100 Subject: [PATCH 009/273] refactor(fake_test_node): prefix package and namespace with autoware (#9249) Signed-off-by: Esteve Fernandez --- .github/CODEOWNERS | 2 +- common/.pages | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 8 ++++---- .../design/fake_test_node-design.md | 8 ++++---- .../fake_test_node/fake_test_node.hpp | 18 ++++++------------ .../fake_test_node/visibility_control.hpp | 6 +++--- .../package.xml | 2 +- .../src/fake_test_node.cpp | 17 +++-------------- .../test/test_fake_test_node.cpp | 6 +++--- .../CMakeLists.txt | 2 +- .../package.xml | 2 +- .../test/test_controller_node.cpp | 4 ++-- .../test/trajectory_follower_test_utils.hpp | 4 ++-- planning/autoware_path_optimizer/package.xml | 2 +- planning/autoware_path_smoother/package.xml | 2 +- .../autoware_path_sampler/package.xml | 2 +- 17 files changed, 35 insertions(+), 52 deletions(-) rename common/{fake_test_node => autoware_fake_test_node}/CHANGELOG.rst (100%) rename common/{fake_test_node => autoware_fake_test_node}/CMakeLists.txt (51%) rename common/{fake_test_node => autoware_fake_test_node}/design/fake_test_node-design.md (91%) rename common/{fake_test_node/include => autoware_fake_test_node/include/autoware}/fake_test_node/fake_test_node.hpp (96%) rename common/{fake_test_node/include => autoware_fake_test_node/include/autoware}/fake_test_node/visibility_control.hpp (90%) rename common/{fake_test_node => autoware_fake_test_node}/package.xml (96%) rename common/{fake_test_node => autoware_fake_test_node}/src/fake_test_node.cpp (90%) rename common/{fake_test_node => autoware_fake_test_node}/test/test_fake_test_node.cpp (94%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 579b60a5be77f..7e6d38636a1b2 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -3,6 +3,7 @@ common/autoware_adapi_specs/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_component_interface_specs/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/autoware_component_interface_tools/** isamu.takagi@tier4.jp +common/autoware_fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_geography_utils/** koji.minoda@tier4.jp common/autoware_goal_distance_calculator/** taiki.tanaka@tier4.jp common/autoware_grid_map_utils/** maxime.clement@tier4.jp @@ -27,7 +28,6 @@ common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp common/component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp -common/fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/glog_component/** takamasa.horibe@tier4.jp common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp diff --git a/common/.pages b/common/.pages index 64d2223329a10..cd0423fa8de79 100644 --- a/common/.pages +++ b/common/.pages @@ -2,7 +2,7 @@ nav: - 'Introduction': common - 'Testing Libraries': - 'autoware_testing': common/autoware_testing/design/autoware_testing-design - - 'fake_test_node': common/fake_test_node/design/fake_test_node-design + - 'autoware_fake_test_node': common/autoware_fake_test_node/design/fake_test_node-design - 'Test Utils': common/autoware_test_utils - 'Common Libraries': - 'autoware_auto_common': diff --git a/common/fake_test_node/CHANGELOG.rst b/common/autoware_fake_test_node/CHANGELOG.rst similarity index 100% rename from common/fake_test_node/CHANGELOG.rst rename to common/autoware_fake_test_node/CHANGELOG.rst diff --git a/common/fake_test_node/CMakeLists.txt b/common/autoware_fake_test_node/CMakeLists.txt similarity index 51% rename from common/fake_test_node/CMakeLists.txt rename to common/autoware_fake_test_node/CMakeLists.txt index 8ad71df2777f3..1be6cdf51ee00 100644 --- a/common/fake_test_node/CMakeLists.txt +++ b/common/autoware_fake_test_node/CMakeLists.txt @@ -1,17 +1,17 @@ cmake_minimum_required(VERSION 3.14) -project(fake_test_node) +project(autoware_fake_test_node) find_package(autoware_cmake REQUIRED) autoware_package() -ament_auto_add_library(fake_test_node SHARED src/fake_test_node.cpp) +ament_auto_add_library(${PROJECT_NAME} SHARED src/fake_test_node.cpp) if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_fake_test_node test/test_fake_test_node.cpp ) - add_dependencies(test_fake_test_node fake_test_node) - target_link_libraries(test_fake_test_node fake_test_node) + add_dependencies(test_fake_test_node ${PROJECT_NAME}) + target_link_libraries(test_fake_test_node ${PROJECT_NAME}) endif() ament_auto_package() diff --git a/common/fake_test_node/design/fake_test_node-design.md b/common/autoware_fake_test_node/design/fake_test_node-design.md similarity index 91% rename from common/fake_test_node/design/fake_test_node-design.md rename to common/autoware_fake_test_node/design/fake_test_node-design.md index c9c040881664a..34142c3529ea9 100644 --- a/common/fake_test_node/design/fake_test_node-design.md +++ b/common/autoware_fake_test_node/design/fake_test_node-design.md @@ -10,8 +10,8 @@ fixture. This package contains a library that introduces two utility classes that can be used in place of custom fixtures described above to write integration tests for a node: -- `autoware::tools::testing::FakeTestNode` - to use as a custom test fixture with `TEST_F` tests -- `autoware::tools::testing::FakeTestNodeParametrized` - to use a custom test fixture with the +- `autoware::fake_test_node::FakeTestNode` - to use as a custom test fixture with `TEST_F` tests +- `autoware::fake_test_node::FakeTestNodeParametrized` - to use a custom test fixture with the parametrized `TEST_P` tests (accepts a template parameter that gets forwarded to `testing::TestWithParam`) @@ -30,10 +30,10 @@ Let's say there is a node `NodeUnderTest` that requires testing. It just subscribes to `std_msgs::msg::Int32` messages and publishes a `std_msgs::msg::Bool` to indicate that the input is positive. To test such a node the following code can be used utilizing the -`autoware::tools::testing::FakeTestNode`: +`autoware::fake_test_node::FakeTestNode`: ```cpp -using FakeNodeFixture = autoware::tools::testing::FakeTestNode; +using FakeNodeFixture = autoware::fake_test_node::FakeTestNode; /// @test Test that we can use a non-parametrized test. TEST_F(FakeNodeFixture, Test) { diff --git a/common/fake_test_node/include/fake_test_node/fake_test_node.hpp b/common/autoware_fake_test_node/include/autoware/fake_test_node/fake_test_node.hpp similarity index 96% rename from common/fake_test_node/include/fake_test_node/fake_test_node.hpp rename to common/autoware_fake_test_node/include/autoware/fake_test_node/fake_test_node.hpp index 9f7fee89776b3..40d45f0689283 100644 --- a/common/fake_test_node/include/fake_test_node/fake_test_node.hpp +++ b/common/autoware_fake_test_node/include/autoware/fake_test_node/fake_test_node.hpp @@ -17,10 +17,10 @@ /// \copyright Copyright 2021 Apex.AI, Inc. /// All rights reserved. -#ifndef FAKE_TEST_NODE__FAKE_TEST_NODE_HPP_ -#define FAKE_TEST_NODE__FAKE_TEST_NODE_HPP_ +#ifndef AUTOWARE__FAKE_TEST_NODE__FAKE_TEST_NODE_HPP_ +#define AUTOWARE__FAKE_TEST_NODE__FAKE_TEST_NODE_HPP_ -#include +#include #include #include @@ -30,11 +30,7 @@ #include #include -namespace autoware -{ -namespace tools -{ -namespace testing +namespace autoware::fake_test_node { /// @@ -237,8 +233,6 @@ class FAKE_TEST_NODE_PUBLIC FakeTestNode : public detail::FakeNodeCore, public : void TearDown() override; }; -} // namespace testing -} // namespace tools -} // namespace autoware +} // namespace autoware::fake_test_node -#endif // FAKE_TEST_NODE__FAKE_TEST_NODE_HPP_ +#endif // AUTOWARE__FAKE_TEST_NODE__FAKE_TEST_NODE_HPP_ diff --git a/common/fake_test_node/include/fake_test_node/visibility_control.hpp b/common/autoware_fake_test_node/include/autoware/fake_test_node/visibility_control.hpp similarity index 90% rename from common/fake_test_node/include/fake_test_node/visibility_control.hpp rename to common/autoware_fake_test_node/include/autoware/fake_test_node/visibility_control.hpp index 62e57eef113f1..d21dbfdbcfc75 100644 --- a/common/fake_test_node/include/fake_test_node/visibility_control.hpp +++ b/common/autoware_fake_test_node/include/autoware/fake_test_node/visibility_control.hpp @@ -17,8 +17,8 @@ /// \copyright Copyright 2021 Apex.AI, Inc. /// All rights reserved. -#ifndef FAKE_TEST_NODE__VISIBILITY_CONTROL_HPP_ -#define FAKE_TEST_NODE__VISIBILITY_CONTROL_HPP_ +#ifndef AUTOWARE__FAKE_TEST_NODE__VISIBILITY_CONTROL_HPP_ +#define AUTOWARE__FAKE_TEST_NODE__VISIBILITY_CONTROL_HPP_ //////////////////////////////////////////////////////////////////////////////// #if defined(__WIN32) @@ -39,4 +39,4 @@ #error "Unsupported Build Configuration" #endif // defined(__WIN32) -#endif // FAKE_TEST_NODE__VISIBILITY_CONTROL_HPP_ +#endif // AUTOWARE__FAKE_TEST_NODE__VISIBILITY_CONTROL_HPP_ diff --git a/common/fake_test_node/package.xml b/common/autoware_fake_test_node/package.xml similarity index 96% rename from common/fake_test_node/package.xml rename to common/autoware_fake_test_node/package.xml index ac2cf75a52423..413f359eafbcc 100644 --- a/common/fake_test_node/package.xml +++ b/common/autoware_fake_test_node/package.xml @@ -1,7 +1,7 @@ - fake_test_node + autoware_fake_test_node 0.38.0 A fake node that we can use in the integration-like cpp tests. Apex.AI, Inc. diff --git a/common/fake_test_node/src/fake_test_node.cpp b/common/autoware_fake_test_node/src/fake_test_node.cpp similarity index 90% rename from common/fake_test_node/src/fake_test_node.cpp rename to common/autoware_fake_test_node/src/fake_test_node.cpp index 1704d371c3a5e..75714c0dd5b08 100644 --- a/common/fake_test_node/src/fake_test_node.cpp +++ b/common/autoware_fake_test_node/src/fake_test_node.cpp @@ -17,12 +17,12 @@ /// \copyright Copyright 2021 Apex.AI, Inc. /// All rights reserved. -#include +#include #include #include -namespace +namespace autoware::fake_test_node { constexpr auto kSpinThread = false; constexpr auto kArgc = 0; @@ -34,15 +34,6 @@ std::string sanitize_test_name(const std::string & name) return sanitize_test_name; } -} // namespace - -namespace autoware -{ -namespace tools -{ -namespace testing -{ - void detail::FakeNodeCore::set_up(const std::string & test_name) { ASSERT_FALSE(rclcpp::ok()); @@ -76,6 +67,4 @@ void FakeTestNode::TearDown() tear_down(); } -} // namespace testing -} // namespace tools -} // namespace autoware +} // namespace autoware::fake_test_node diff --git a/common/fake_test_node/test/test_fake_test_node.cpp b/common/autoware_fake_test_node/test/test_fake_test_node.cpp similarity index 94% rename from common/fake_test_node/test/test_fake_test_node.cpp rename to common/autoware_fake_test_node/test/test_fake_test_node.cpp index 77e9294cb48c2..886433ed5fff6 100644 --- a/common/fake_test_node/test/test_fake_test_node.cpp +++ b/common/autoware_fake_test_node/test/test_fake_test_node.cpp @@ -17,7 +17,7 @@ /// \copyright Copyright 2021 Apex.AI, Inc. /// All rights reserved. -#include +#include #include #include @@ -30,8 +30,8 @@ using bool8_t = bool; -using FakeNodeFixture = autoware::tools::testing::FakeTestNode; -using FakeNodeFixtureParametrized = autoware::tools::testing::FakeTestNodeParametrized; +using FakeNodeFixture = autoware::fake_test_node::FakeTestNode; +using FakeNodeFixtureParametrized = autoware::fake_test_node::FakeTestNodeParametrized; using std_msgs::msg::Bool; using std_msgs::msg::Int32; diff --git a/control/autoware_trajectory_follower_node/CMakeLists.txt b/control/autoware_trajectory_follower_node/CMakeLists.txt index 26488bd474149..90fa1b0319919 100644 --- a/control/autoware_trajectory_follower_node/CMakeLists.txt +++ b/control/autoware_trajectory_follower_node/CMakeLists.txt @@ -33,7 +33,7 @@ if(BUILD_TESTING) test/trajectory_follower_test_utils.hpp test/test_controller_node.cpp ) - ament_target_dependencies(${TRAJECTORY_FOLLOWER_NODES_TEST} fake_test_node) + ament_target_dependencies(${TRAJECTORY_FOLLOWER_NODES_TEST} autoware_fake_test_node) target_link_libraries( ${TRAJECTORY_FOLLOWER_NODES_TEST} ${CONTROLLER_NODE}) diff --git a/control/autoware_trajectory_follower_node/package.xml b/control/autoware_trajectory_follower_node/package.xml index 848eb7d3b6d10..86a2592ebf5f4 100644 --- a/control/autoware_trajectory_follower_node/package.xml +++ b/control/autoware_trajectory_follower_node/package.xml @@ -40,9 +40,9 @@ ament_index_cpp ament_index_python ament_lint_auto + autoware_fake_test_node autoware_lint_common autoware_testing - fake_test_node ros_testing diff --git a/control/autoware_trajectory_follower_node/test/test_controller_node.cpp b/control/autoware_trajectory_follower_node/test/test_controller_node.cpp index 71813c8a5c5d8..40e4366d9aa17 100644 --- a/control/autoware_trajectory_follower_node/test/test_controller_node.cpp +++ b/control/autoware_trajectory_follower_node/test/test_controller_node.cpp @@ -13,8 +13,8 @@ // limitations under the License. #include "ament_index_cpp/get_package_share_directory.hpp" +#include "autoware/fake_test_node/fake_test_node.hpp" #include "autoware/trajectory_follower_node/controller_node.hpp" -#include "fake_test_node/fake_test_node.hpp" #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "rclcpp/time.hpp" @@ -42,7 +42,7 @@ using SteeringReport = autoware_vehicle_msgs::msg::SteeringReport; using autoware_adapi_v1_msgs::msg::OperationModeState; using geometry_msgs::msg::AccelWithCovarianceStamped; -using FakeNodeFixture = autoware::tools::testing::FakeTestNode; +using FakeNodeFixture = autoware::fake_test_node::FakeTestNode; const rclcpp::Duration one_second(1, 0); diff --git a/control/autoware_trajectory_follower_node/test/trajectory_follower_test_utils.hpp b/control/autoware_trajectory_follower_node/test/trajectory_follower_test_utils.hpp index 1ccffcaf7f3e3..31c5bad619cb9 100644 --- a/control/autoware_trajectory_follower_node/test/trajectory_follower_test_utils.hpp +++ b/control/autoware_trajectory_follower_node/test/trajectory_follower_test_utils.hpp @@ -15,7 +15,7 @@ #ifndef TRAJECTORY_FOLLOWER_TEST_UTILS_HPP_ #define TRAJECTORY_FOLLOWER_TEST_UTILS_HPP_ -#include "fake_test_node/fake_test_node.hpp" +#include "autoware/fake_test_node/fake_test_node.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp/time.hpp" #include "tf2_ros/static_transform_broadcaster.h" @@ -27,7 +27,7 @@ namespace test_utils { -using FakeNodeFixture = autoware::tools::testing::FakeTestNode; +using FakeNodeFixture = autoware::fake_test_node::FakeTestNode; inline void waitForMessage( const std::shared_ptr & node, FakeNodeFixture * fixture, const bool & received_flag, diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml index 5dd763494ada0..7c5b1e68e759a 100644 --- a/planning/autoware_path_optimizer/package.xml +++ b/planning/autoware_path_optimizer/package.xml @@ -34,9 +34,9 @@ ament_cmake_ros ament_index_python ament_lint_auto + autoware_fake_test_node autoware_lint_common autoware_testing - fake_test_node ament_cmake diff --git a/planning/autoware_path_smoother/package.xml b/planning/autoware_path_smoother/package.xml index a9ead8e54d104..6c8b3efec678b 100644 --- a/planning/autoware_path_smoother/package.xml +++ b/planning/autoware_path_smoother/package.xml @@ -31,9 +31,9 @@ ament_cmake_ros ament_index_python ament_lint_auto + autoware_fake_test_node autoware_lint_common autoware_testing - fake_test_node ament_cmake diff --git a/planning/sampling_based_planner/autoware_path_sampler/package.xml b/planning/sampling_based_planner/autoware_path_sampler/package.xml index 188839c805179..c4dafda08a14c 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_path_sampler/package.xml @@ -34,9 +34,9 @@ ament_cmake_ros ament_index_python ament_lint_auto + autoware_fake_test_node autoware_lint_common autoware_testing - fake_test_node ament_cmake From cdb6e888b4b320b29bad86b745cb0908dc2282ef Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 14 Nov 2024 12:08:14 +0000 Subject: [PATCH 010/273] chore: update CODEOWNERS (#9232) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 27 +++++++++++++-------------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 7e6d38636a1b2..61af2edc5b516 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -3,8 +3,9 @@ common/autoware_adapi_specs/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp common/autoware_auto_common/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_component_interface_specs/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/autoware_component_interface_tools/** isamu.takagi@tier4.jp +common/autoware_component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/autoware_fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -common/autoware_geography_utils/** koji.minoda@tier4.jp +common/autoware_geography_utils/** anh.nguyen.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp common/autoware_goal_distance_calculator/** taiki.tanaka@tier4.jp common/autoware_grid_map_utils/** maxime.clement@tier4.jp common/autoware_interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp @@ -23,11 +24,10 @@ common/autoware_signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.j common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -common/autoware_trajectory/** yukinari.hisaki.2@tier4.jp takayuki.murooka@tier4.jp mamoru.sobue@tier4.jp +common/autoware_trajectory/** mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yukinari.hisaki.2@tier4.jp common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp -common/component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/glog_component/** takamasa.horibe@tier4.jp common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp @@ -61,12 +61,11 @@ control/autoware_vehicle_cmd_gate/** takamasa.horibe@tier4.jp tomoya.kimura@tier control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/predicted_path_checker/** berkay@leodrive.ai evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp temkei.kem@tier4.jp -evaluator/autoware_evaluator_utils/** daniel.sanchez@tier4.jp takayuki.murooka@tier4.jp -evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp -evaluator/scenario_simulator_v2_adapter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp +evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp temkei.kem@tier4.jp evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp evaluator/localization_evaluator/** dominik.jargot@robotec.ai koji.minoda@tier4.jp evaluator/perception_online_evaluator/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp +evaluator/scenario_simulator_v2_adapter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp launch/tier4_control_launch/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp launch/tier4_localization_launch/** 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 @@ -105,7 +104,7 @@ map/map_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakam perception/autoware_bytetrack/** manato.hirabayashi@tier4.jp yoshi.ri@tier4.jp perception/autoware_cluster_merger/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp perception/autoware_compare_map_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp yukihiro.saito@tier4.jp -perception/autoware_crosswalk_traffic_light_estimator/** satoshi.ota@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp masato.saeki@tier4.jp +perception/autoware_crosswalk_traffic_light_estimator/** masato.saeki@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/autoware_detected_object_feature_remover/** kotaro.uetake@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp perception/autoware_detected_object_validation/** dai.nguyen@tier4.jp shintaro.tomie@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/autoware_detection_by_tracker/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @@ -135,13 +134,13 @@ perception/autoware_tensorrt_classifier/** kotaro.uetake@tier4.jp shunsuke.miura perception/autoware_tensorrt_common/** amadeusz.szymko.2@tier4.jp dan.umeda@tier4.jp kenzo.lobos@tier4.jp manato.hirabayashi@tier4.jp perception/autoware_tensorrt_yolox/** dan.umeda@tier4.jp kotaro.uetake@tier4.jp manato.hirabayashi@tier4.jp perception/autoware_tracking_object_merger/** taekjin.lee@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp -perception/autoware_traffic_light_arbiter/** kenzo.lobos@tier4.jp shunsuke.miura@tier4.jp masato.saeki@tier4.jp -perception/autoware_traffic_light_classifier/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp masato.saeki@tier4.jp -perception/autoware_traffic_light_fine_detector/** shintaro.tomie@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp masato.saeki@tier4.jp -perception/autoware_traffic_light_map_based_detector/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp masato.saeki@tier4.jp -perception/autoware_traffic_light_multi_camera_fusion/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp masato.saeki@tier4.jp -perception/autoware_traffic_light_occlusion_predictor/** shunsuke.miura@tier4.jp tao.zhong@tier4.jp masato.saeki@tier4.jp -perception/autoware_traffic_light_visualization/** tao.zhong@tier4.jp yukihiro.saito@tier4.jp masato.saeki@tier4.jp +perception/autoware_traffic_light_arbiter/** kenzo.lobos@tier4.jp masato.saeki@tier4.jp shunsuke.miura@tier4.jp +perception/autoware_traffic_light_classifier/** masato.saeki@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp +perception/autoware_traffic_light_fine_detector/** masato.saeki@tier4.jp shintaro.tomie@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp +perception/autoware_traffic_light_map_based_detector/** masato.saeki@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp +perception/autoware_traffic_light_multi_camera_fusion/** masato.saeki@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp +perception/autoware_traffic_light_occlusion_predictor/** masato.saeki@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp +perception/autoware_traffic_light_visualization/** masato.saeki@tier4.jp tao.zhong@tier4.jp yukihiro.saito@tier4.jp perception/perception_utils/** shunsuke.miura@tier4.jp yoshi.ri@tier4.jp planning/autoware_costmap_generator/** kosuke.takeuchi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp planning/autoware_external_velocity_limit_selector/** satoshi.ota@tier4.jp shinnosuke.hirakawa@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp From 778fb4528486d7ddf2fdfb2b235d9b40c3f2c46e Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Fri, 15 Nov 2024 11:31:02 +0900 Subject: [PATCH 011/273] fix(freespace_planner): fix is near target check (#9327) * fix is_near_target_check Signed-off-by: mohammad alqudah * update unit test Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah --- .../src/autoware_freespace_planner/utils.cpp | 6 +++--- .../test/test_freespace_planner_utils.cpp | 10 ++++++++++ 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp index badd9c824468a..ef22a21d33eb1 100644 --- a/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp @@ -171,8 +171,8 @@ bool is_stopped( bool is_near_target(const Pose & target_pose, const Pose & current_pose, const double th_distance_m) { - const double long_disp_to_target = - autoware::universe_utils::calcLongitudinalDeviation(target_pose, current_pose.position); - return std::abs(long_disp_to_target) < th_distance_m; + const auto pose_dev = autoware::universe_utils::calcPoseDeviation(target_pose, current_pose); + return abs(pose_dev.yaw) < M_PI_2 && abs(pose_dev.longitudinal) < th_distance_m && + abs(pose_dev.lateral) < th_distance_m; } } // namespace autoware::freespace_planner::utils diff --git a/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp index 071f7e2cfcaa0..7c795a8eb7b85 100644 --- a/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp +++ b/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp @@ -153,9 +153,11 @@ TEST(FreespacePlannerUtilsTest, testIsNearTarget) const auto trajectory = get_trajectory(0ul); const auto target_pose = trajectory.points.back().pose; + static constexpr double eps = 0.01; auto current_pose = target_pose; current_pose.position.x -= 1.0; current_pose.position.y += 1.0; + current_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(M_PI_2 + eps); const double th_distance_m = 0.5; @@ -163,6 +165,14 @@ TEST(FreespacePlannerUtilsTest, testIsNearTarget) autoware::freespace_planner::utils::is_near_target(target_pose, current_pose, th_distance_m)); current_pose.position.x += 0.6; + EXPECT_FALSE( + autoware::freespace_planner::utils::is_near_target(target_pose, current_pose, th_distance_m)); + + current_pose.position.y -= 0.6; + EXPECT_FALSE( + autoware::freespace_planner::utils::is_near_target(target_pose, current_pose, th_distance_m)); + + current_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(M_PI_4); EXPECT_TRUE( autoware::freespace_planner::utils::is_near_target(target_pose, current_pose, th_distance_m)); } From 3adfb07cfb70e23d7d00f0e0fbde960cd27d8bd7 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 15 Nov 2024 11:36:18 +0900 Subject: [PATCH 012/273] refactor(static obstacle avoidance): remove redundant calculation (#9326) * refactor bases on clang tidy Signed-off-by: Go Sakayori * refactor extend backward length Signed-off-by: Go Sakayori * mover redundant calculation in getRoadShoulderDistance Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../src/scene.cpp | 20 ++++++----- .../src/utils.cpp | 36 ++++++++----------- 2 files changed, 25 insertions(+), 31 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 380e93338b1f0..f30e09fe6475f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -24,6 +24,7 @@ #include "autoware/behavior_path_static_obstacle_avoidance_module/debug.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp" +#include #include #include #include @@ -574,7 +575,7 @@ void StaticObstacleAvoidanceModule::fillEgoStatus( } const auto registered_sl_force_deactivated = - [&](const std::string & direction, const RegisteredShiftLineArray shift_line_array) { + [&](const std::string & direction, const RegisteredShiftLineArray & shift_line_array) { return std::any_of( shift_line_array.begin(), shift_line_array.end(), [&](const auto & shift_line) { return rtc_interface_ptr_map_.at(direction)->isForceDeactivated(shift_line.uuid); @@ -611,7 +612,7 @@ void StaticObstacleAvoidanceModule::fillEgoStatus( }; auto registered_sl_force_activated = - [&](const std::string & direction, const RegisteredShiftLineArray shift_line_array) { + [&](const std::string & direction, const RegisteredShiftLineArray & shift_line_array) { return std::any_of( shift_line_array.begin(), shift_line_array.end(), [&](const auto & shift_line) { return rtc_interface_ptr_map_.at(direction)->isForceActivated(shift_line.uuid); @@ -916,13 +917,14 @@ PathWithLaneId StaticObstacleAvoidanceModule::extendBackwardLength( } size_t clip_idx = 0; - for (size_t i = 0; i < prev_ego_idx; ++i) { - if ( - backward_length > - autoware::motion_utils::calcSignedArcLength(previous_path.points, clip_idx, *prev_ego_idx)) { + double accumulated_length = 0.0; + for (size_t i = prev_ego_idx.value(); i > 0; i--) { + accumulated_length += autoware::universe_utils::calcDistance2d( + previous_path.points.at(i - 1), previous_path.points.at(i)); + if (accumulated_length > backward_length) { + clip_idx = i; break; } - clip_idx = i; } PathWithLaneId extended_path{}; @@ -1245,8 +1247,8 @@ void StaticObstacleAvoidanceModule::updatePathShifter(const AvoidLineArray & shi generator_.setRawRegisteredShiftLine(shift_lines, avoid_data_); const auto sl = helper_->getMainShiftLine(shift_lines); - const auto sl_front = shift_lines.front(); - const auto sl_back = shift_lines.back(); + const auto & sl_front = shift_lines.front(); + const auto & sl_back = shift_lines.back(); const auto relative_longitudinal = sl_back.end_longitudinal - sl_front.start_longitudinal; if (helper_->getRelativeShiftToPath(sl) > 0.0) { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 72b75586d42c5..84978286a96c6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -545,11 +545,7 @@ bool isParkedVehicle( object.to_centerline = lanelet::utils::getArcCoordinates(data.current_lanelets, object.getPose()).distance; - if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) { - return false; - } - - return true; + return std::abs(object.to_centerline) >= parameters->threshold_distance_object_is_on_center; } bool isCloseToStopFactor( @@ -1091,16 +1087,17 @@ double getRoadShoulderDistance( return 0.0; } + const auto centerline_pose = + lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object.getPosition()); + // TODO(Satoshi OTA): check if the basic point is on right or left of bound. + const auto bound = isOnRight(object) ? data.left_bound : data.right_bound; + const auto envelope_polygon_width = boost::geometry::area(object.envelope_poly) / + std::max(object.length, 1e-3); // prevent division by zero + std::vector> intersects; for (const auto & p1 : object.overhang_points) { - const auto centerline_pose = - lanelet::utils::getClosestCenterPose(object.overhang_lanelet, object.getPosition()); const auto p_tmp = geometry_msgs::build().position(p1.second).orientation(centerline_pose.orientation); - - // TODO(Satoshi OTA): check if the basic point is on right or left of bound. - const auto bound = isOnRight(object) ? data.left_bound : data.right_bound; - for (size_t i = 1; i < bound.size(); i++) { { const auto p2 = @@ -1114,11 +1111,6 @@ double getRoadShoulderDistance( break; } } - - const auto envelope_polygon_width = - boost::geometry::area(object.envelope_poly) / - std::max(object.length, 1e-3); // prevent division by zero - { const auto p2 = calcOffsetPose(p_tmp, 0.0, (isOnRight(object) ? -0.5 : 0.5) * envelope_polygon_width, 0.0) @@ -1301,7 +1293,7 @@ std::vector calcParentIds(const AvoidLineArray & lines1, const AvoidLine & for (const auto & al : lines1) { const auto p_s = al.start_longitudinal; const auto p_e = al.end_longitudinal; - const auto has_overlap = !(p_e < lines2.start_longitudinal || lines2.end_longitudinal < p_s); + const auto has_overlap = p_e >= lines2.start_longitudinal && lines2.end_longitudinal >= p_s; if (!has_overlap) { continue; @@ -1315,10 +1307,11 @@ std::vector calcParentIds(const AvoidLineArray & lines1, const AvoidLine & double lerpShiftLengthOnArc(double arc, const AvoidLine & ap) { if (ap.start_longitudinal <= arc && arc < ap.end_longitudinal) { - if (std::abs(ap.getRelativeLongitudinal()) < 1.0e-5) { + const auto relative_longitudinal = ap.getRelativeLongitudinal(); + if (std::abs(relative_longitudinal) < 1.0e-5) { return ap.end_shift_length; } - const auto start_weight = (ap.end_longitudinal - arc) / ap.getRelativeLongitudinal(); + const auto start_weight = (ap.end_longitudinal - arc) / relative_longitudinal; return start_weight * ap.start_shift_length + (1.0 - start_weight) * ap.end_shift_length; } return 0.0; @@ -1339,7 +1332,6 @@ void fillLongitudinalAndLengthByClosestEnvelopeFootprint( } obj.longitudinal = min_distance; obj.length = max_distance - min_distance; - return; } std::vector> calcEnvelopeOverhangDistance( @@ -2220,9 +2212,9 @@ std::vector getSafetyCheckTargetObjects( }); }; - const auto to_predicted_objects = [&p, ¶meters](const auto & objects) { + const auto to_predicted_objects = [¶meters](const auto & objects) { PredictedObjects ret{}; - std::for_each(objects.begin(), objects.end(), [&p, &ret, ¶meters](const auto & object) { + std::for_each(objects.begin(), objects.end(), [&ret, ¶meters](const auto & object) { if (filtering_utils::isSafetyCheckTargetObjectType(object.object, parameters)) { // check only moving objects if (filtering_utils::isMovingObject(object, parameters) || !object.is_parked) { From 3b623fbd8cd0ffc3afd1bd0ac9f212386a97e078 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 15 Nov 2024 13:53:30 +0900 Subject: [PATCH 013/273] feat(behavior_velocity_stop_line): replace autoware_motion_utils to autoware_trajectory (#9299) * feat(behavior_velocity_stop_line): replace autoware_motion_utils to autoware_trajectory Signed-off-by: Y.Hisaki * update Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../factor/velocity_factor_interface.hpp | 3 + .../src/factor/velocity_factor_interface.cpp | 9 ++ .../autoware/trajectory/detail/utils.hpp | 2 +- .../autoware_trajectory/src/detail/util.cpp | 2 +- .../package.xml | 1 + .../src/debug.cpp | 8 +- .../src/manager.cpp | 3 +- .../src/manager.hpp | 6 +- .../src/scene.cpp | 113 ++++++++---------- .../src/scene.hpp | 34 +----- 10 files changed, 80 insertions(+), 101 deletions(-) diff --git a/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp index 30eca6927db34..2fcde52ec7c81 100644 --- a/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/factor/velocity_factor_interface.hpp @@ -44,6 +44,9 @@ class VelocityFactorInterface const std::vector & points, const Pose & curr_pose, const Pose & stop_pose, const VelocityFactorStatus status, const std::string & detail = ""); + void set( + const double & distance, const VelocityFactorStatus & status, const std::string & detail = ""); + private: VelocityFactorBehavior behavior_{VelocityFactor::UNKNOWN}; VelocityFactor velocity_factor_{}; diff --git a/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp b/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp index e405cdb655c02..6a1ddff453bd0 100644 --- a/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp +++ b/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp @@ -36,6 +36,15 @@ void VelocityFactorInterface::set( velocity_factor_.detail = detail; } +void VelocityFactorInterface::set( + const double & distance, const VelocityFactorStatus & status, const std::string & detail) +{ + velocity_factor_.behavior = behavior_; + velocity_factor_.distance = static_cast(distance); + velocity_factor_.status = status; + velocity_factor_.detail = detail; +} + template void VelocityFactorInterface::set( const std::vector &, const Pose &, const Pose &, const VelocityFactorStatus, const std::string &); diff --git a/common/autoware_trajectory/include/autoware/trajectory/detail/utils.hpp b/common/autoware_trajectory/include/autoware/trajectory/detail/utils.hpp index 9a33152a7dfdb..3346d4ce8104f 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/detail/utils.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/detail/utils.hpp @@ -36,7 +36,7 @@ namespace autoware::trajectory::detail */ geometry_msgs::msg::Point to_point(const geometry_msgs::msg::Point & p); geometry_msgs::msg::Point to_point(const geometry_msgs::msg::Pose & p); -geometry_msgs::msg::Point to_point(const Eigen::Ref & p); +geometry_msgs::msg::Point to_point(const Eigen::Vector2d & p); geometry_msgs::msg::Point to_point(const autoware_planning_msgs::msg::PathPoint & p); geometry_msgs::msg::Point to_point(const tier4_planning_msgs::msg::PathPointWithLaneId & p); geometry_msgs::msg::Point to_point(const lanelet::BasicPoint2d & p); diff --git a/common/autoware_trajectory/src/detail/util.cpp b/common/autoware_trajectory/src/detail/util.cpp index 8cfb8029629cb..4c9649ef1f3ab 100644 --- a/common/autoware_trajectory/src/detail/util.cpp +++ b/common/autoware_trajectory/src/detail/util.cpp @@ -30,7 +30,7 @@ geometry_msgs::msg::Point to_point(const geometry_msgs::msg::Pose & p) return p.position; } -geometry_msgs::msg::Point to_point(const Eigen::Ref & p) +geometry_msgs::msg::Point to_point(const Eigen::Vector2d & p) { geometry_msgs::msg::Point point; point.x = p(0); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml index 464a5d0f09bf7..68a8d919512b1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml @@ -23,6 +23,7 @@ autoware_motion_utils autoware_planning_msgs autoware_route_handler + autoware_trajectory eigen geometry_msgs pluginlib diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp index 29295f41cdf04..573a260138679 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware/behavior_velocity_planner_common/utilization/util.hpp" +#include "autoware/motion_utils/marker/virtual_wall_marker_creator.hpp" +#include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware/universe_utils/ros/marker_helper.hpp" #include "scene.hpp" -#include -#include -#include -#include #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp index 4dcd0309ce526..ffdcea16b45b5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp @@ -15,6 +15,7 @@ #include "manager.hpp" #include "autoware/universe_utils/ros/parameter.hpp" +#include "autoware_lanelet2_extension/utility/query.hpp" #include #include @@ -57,7 +58,7 @@ std::vector StopLineModuleManager::getStopLinesWithLaneIdOnP } for (const auto & stop_line : traffic_sign_reg_elem->refLines()) { - stop_lines_with_lane_id.push_back(std::make_pair(stop_line, lane_id)); + stop_lines_with_lane_id.emplace_back(stop_line, lane_id); } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp index 2a008ce1700ab..b83a4f94e9a1f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp @@ -15,11 +15,11 @@ #ifndef MANAGER_HPP_ #define MANAGER_HPP_ +#include "autoware/behavior_velocity_planner_common/plugin_interface.hpp" +#include "autoware/behavior_velocity_planner_common/plugin_wrapper.hpp" +#include "autoware/behavior_velocity_planner_common/scene_module_interface.hpp" #include "scene.hpp" -#include -#include -#include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index 0500d22d425cd..6a4b85cd6926c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -14,60 +14,66 @@ #include "scene.hpp" -#include -#include -#include -#include +#include "autoware/behavior_velocity_planner_common/utilization/util.hpp" +#include "autoware/trajectory/path_point_with_lane_id.hpp" -#include -#include +#include namespace autoware::behavior_velocity_planner { -namespace bg = boost::geometry; StopLineModule::StopLineModule( - const int64_t module_id, const size_t lane_id, const lanelet::ConstLineString3d & stop_line, - const PlannerParam & planner_param, const rclcpp::Logger logger, + const int64_t module_id, const size_t lane_id, lanelet::ConstLineString3d stop_line, + const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), lane_id_(lane_id), - stop_line_(stop_line), + stop_line_(std::move(stop_line)), state_(State::APPROACH), + planner_param_(planner_param), debug_data_() { velocity_factor_.init(PlanningBehavior::STOP_SIGN); - planner_param_ = planner_param; } bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) { - universe_utils::ScopedTimeTrack st( - std::string(__func__) + " (lane_id:=" + std::to_string(module_id_) + ")", *getTimeKeeper()); + auto trajectory = + trajectory::Trajectory::Builder{}.build( + path->points); + + if (!trajectory) { + return true; + } + debug_data_ = DebugData(); - if (path->points.empty()) return true; - const auto base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; debug_data_.base_link2front = base_link2front; - first_stop_path_point_distance_ = autoware::motion_utils::calcArcLength(path->points); + first_stop_path_point_distance_ = trajectory->length(); *stop_reason = planning_utils::initializeStopReason(StopReason::STOP_LINE); const LineString2d stop_line = planning_utils::extendLine( stop_line_[0], stop_line_[1], planner_data_->stop_line_extend_length); - time_keeper_->start_track("createTargetPoint"); - // Calculate stop pose and insert index - const auto stop_point = arc_lane_utils::createTargetPoint( - *path, stop_line, planner_param_.stop_margin, - planner_data_->vehicle_info_.max_longitudinal_offset_m); - time_keeper_->end_track("createTargetPoint"); + // Calculate intersection with stop line + const auto trajectory_stop_line_intersection = + trajectory->crossed(stop_line.front(), stop_line.back()); + // If no collision found, do nothing - if (!stop_point) { + if (!trajectory_stop_line_intersection) { RCLCPP_DEBUG_THROTTLE(logger_, *clock_, 5000 /* ms */, "is no collision"); return true; } - const auto stop_point_idx = stop_point->first; - auto stop_pose = stop_point->second; + const double stop_point_s = + *trajectory_stop_line_intersection - + (base_link2front + planner_param_.stop_margin); // consider vehicle length and stop margin + + if (stop_point_s < 0.0) { + return true; + } + + const auto stop_pose = trajectory->compute(stop_point_s); /** * @brief : calculate signed arc length consider stop margin from stop line @@ -75,35 +81,26 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop * |----------------------------| * s---ego----------x--|--------g */ - time_keeper_->start_track( - "calcSegmentIndexFromPointIndex & findEgoSegmentIndex & calcSignedArcLength"); - const size_t stop_line_seg_idx = planning_utils::calcSegmentIndexFromPointIndex( - path->points, stop_pose.position, stop_point_idx); - const size_t current_seg_idx = findEgoSegmentIndex(path->points); - const double signed_arc_dist_to_stop_point = autoware::motion_utils::calcSignedArcLength( - path->points, planner_data_->current_odometry->pose.position, current_seg_idx, - stop_pose.position, stop_line_seg_idx); - time_keeper_->end_track( - "calcSegmentIndexFromPointIndex & findEgoSegmentIndex & calcSignedArcLength"); + const double ego_on_trajectory_s = + trajectory->closest(planner_data_->current_odometry->pose.position); + const double signed_arc_dist_to_stop_point = stop_point_s - ego_on_trajectory_s; + switch (state_) { case State::APPROACH: { // Insert stop pose - planning_utils::insertStopPoint(stop_pose.position, stop_line_seg_idx, *path); + trajectory->longitudinal_velocity_mps.range(stop_point_s, trajectory->length()).set(0.0); - // Update first stop index - first_stop_path_point_distance_ = autoware::motion_utils::calcSignedArcLength( - path->points, 0, stop_pose.position, stop_line_seg_idx); - debug_data_.stop_pose = stop_pose; + // Update first stop path point distance + first_stop_path_point_distance_ = stop_point_s; + debug_data_.stop_pose = stop_pose.point.pose; // Get stop point and stop factor { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = stop_pose; + stop_factor.stop_pose = stop_pose.point.pose; stop_factor.stop_factor_points.push_back(getCenterOfStopLine(stop_line_)); planning_utils::appendStopReason(stop_factor, stop_reason); - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, - VelocityFactor::APPROACHING); + velocity_factor_.set(signed_arc_dist_to_stop_point, VelocityFactor::APPROACHING); } // Move to stopped state if stopped @@ -125,34 +122,22 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop } case State::STOPPED: { - // Change state after vehicle departure - const auto stopped_pose = autoware::motion_utils::calcLongitudinalOffsetPose( - path->points, planner_data_->current_odometry->pose.position, 0.0); - - if (!stopped_pose) { - break; - } - - SegmentIndexWithPose ego_pos_on_path; - ego_pos_on_path.pose = stopped_pose.value(); - ego_pos_on_path.index = findEgoSegmentIndex(path->points); - // Insert stop pose - planning_utils::insertStopPoint(ego_pos_on_path.pose.position, ego_pos_on_path.index, *path); - - debug_data_.stop_pose = stop_pose; + trajectory->longitudinal_velocity_mps.range(ego_on_trajectory_s, trajectory->length()) + .set(0.0); + const auto ego_pos_on_path = trajectory->compute(ego_on_trajectory_s).point.pose; + debug_data_.stop_pose = ego_pos_on_path; // Get stop point and stop factor { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = ego_pos_on_path.pose; + stop_factor.stop_pose = ego_pos_on_path; stop_factor.stop_factor_points.push_back(getCenterOfStopLine(stop_line_)); planning_utils::appendStopReason(stop_factor, stop_reason); - velocity_factor_.set( - path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::STOPPED); + velocity_factor_.set(signed_arc_dist_to_stop_point, VelocityFactor::STOPPED); } - const auto elapsed_time = (clock_->now() - *stopped_time_).seconds(); + const double elapsed_time = (clock_->now() - *stopped_time_).seconds(); if (planner_param_.stop_duration_sec < elapsed_time) { RCLCPP_INFO(logger_, "STOPPED -> START"); @@ -175,6 +160,8 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop } } + path->points = trajectory->restore(); + return true; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp index 78aec89adb063..cb48aabe57c1a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp @@ -15,23 +15,20 @@ #ifndef SCENE_HPP_ #define SCENE_HPP_ +#include "autoware/behavior_velocity_planner_common/scene_module_interface.hpp" +#include "autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp" +#include "autoware/behavior_velocity_planner_common/utilization/util.hpp" + #include -#include -#include #include #include #define EIGEN_MPL2_ONLY #include #include -#include -#include -#include -#include #include #include -#include namespace autoware::behavior_velocity_planner { @@ -42,24 +39,6 @@ class StopLineModule : public SceneModuleInterface public: enum class State { APPROACH, STOPPED, START }; - struct SegmentIndexWithPose - { - size_t index; - geometry_msgs::msg::Pose pose; - }; - - struct SegmentIndexWithPoint2d - { - size_t index; - Point2d point; - }; - - struct SegmentIndexWithOffset - { - size_t index; - double offset; - }; - struct DebugData { double base_link2front; @@ -77,10 +56,9 @@ class StopLineModule : public SceneModuleInterface bool show_stop_line_collision_check; }; -public: StopLineModule( - const int64_t module_id, const size_t lane_id, const lanelet::ConstLineString3d & stop_line, - const PlannerParam & planner_param, const rclcpp::Logger logger, + const int64_t module_id, const size_t lane_id, lanelet::ConstLineString3d stop_line, + const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; From e54020e87cc199a318d6c5066fd5d36c63c677da Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Date: Fri, 15 Nov 2024 14:52:25 +0900 Subject: [PATCH 014/273] test(bpp_common): add tests for the static drivable area (#9324) Signed-off-by: Maxime CLEMENT --- .../autoware_test_utils.hpp | 13 + .../src/autoware_test_utils.cpp | 13 + .../CMakeLists.txt | 1 + .../static_drivable_area.hpp | 58 +- .../static_drivable_area.cpp | 15 +- .../test/test_static_drivable_area.cpp | 528 ++++++++++++++++++ 6 files changed, 620 insertions(+), 8 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_static_drivable_area.cpp diff --git a/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp index c760ba1c94b45..3721dc67526b5 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/autoware_test_utils.hpp @@ -330,6 +330,19 @@ void updateNodeOptions( */ PathWithLaneId loadPathWithLaneIdInYaml(); +/** + * @brief create a straight lanelet from 2 segments defined by 4 points + * @param [in] left0 start of the left segment + * @param [in] left1 end of the left segment + * @param [in] right0 start of the right segment + * @param [in] right1 end of the right segment + * @return a ConstLanelet with the given left and right bounds and a unique lanelet id + * + */ +lanelet::ConstLanelet make_lanelet( + const lanelet::BasicPoint2d & left0, const lanelet::BasicPoint2d & left1, + const lanelet::BasicPoint2d & right0, const lanelet::BasicPoint2d & right1); + /** * @brief Generates a trajectory with specified parameters. * diff --git a/common/autoware_test_utils/src/autoware_test_utils.cpp b/common/autoware_test_utils/src/autoware_test_utils.cpp index 1e2c7b50912f6..696f58d5e19e8 100644 --- a/common/autoware_test_utils/src/autoware_test_utils.cpp +++ b/common/autoware_test_utils/src/autoware_test_utils.cpp @@ -313,6 +313,19 @@ PathWithLaneId loadPathWithLaneIdInYaml() return parse(yaml_path); } +lanelet::ConstLanelet make_lanelet( + const lanelet::BasicPoint2d & left0, const lanelet::BasicPoint2d & left1, + const lanelet::BasicPoint2d & right0, const lanelet::BasicPoint2d & right1) +{ + lanelet::LineString3d left_bound; + left_bound.push_back(lanelet::Point3d(lanelet::InvalId, left0.x(), left0.y(), 0.0)); + left_bound.push_back(lanelet::Point3d(lanelet::InvalId, left1.x(), left1.y(), 0.0)); + lanelet::LineString3d right_bound; + right_bound.push_back(lanelet::Point3d(lanelet::InvalId, right0.x(), right0.y(), 0.0)); + right_bound.push_back(lanelet::Point3d(lanelet::InvalId, right1.x(), right1.y(), 0.0)); + return {lanelet::utils::getId(), left_bound, right_bound}; +} + std::optional resolve_pkg_share_uri(const std::string & uri_path) { std::smatch match; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt index bcc8dd9d9f299..22faf1a6375d8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt @@ -45,6 +45,7 @@ if(BUILD_TESTING) ament_add_ros_isolated_gmock(test_${PROJECT_NAME}_drivable_area_expansion test/test_drivable_area_expansion.cpp test/test_footprints.cpp + test/test_static_drivable_area.cpp ) target_link_libraries(test_${PROJECT_NAME}_drivable_area_expansion diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp index f393ec18f8a32..23f0de6f5348f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp @@ -25,12 +25,30 @@ namespace autoware::behavior_path_planner::utils { using autoware::behavior_path_planner::drivable_area_expansion::DrivableAreaExpansionParameters; +/** + * @brief finds the index of the first lane in the provided vector that overlaps with a preceding + * lane (excluding the immediate predecessor in the vector) + * @param [ink] lanes vector of DrivableLanes + * @return the index of the first overlapping lane (if any) + */ std::optional getOverlappedLaneletId(const std::vector & lanes); +/** + * @brief modify a path to only keep points inside the given lanes (before any lane overlap) + * @details the path point lanelet_ids are used to determine if they are inside a lanelet + * @param [inout] path path to be cut + * @param [in] lanes lanes used to cut the path + * @return the shortened lanes without overlaps + */ std::vector cutOverlappedLanes( PathWithLaneId & path, const std::vector & lanes); -std::vector generateDrivableLanes(const lanelet::ConstLanelets & current_lanes); +/** + * @brief generate DrivableLanes objects from a sequence of lanelets + * @param [in] lanelets sequence of lanelets + * @return a vector of DrivableLanes constructed from the given lanelets + */ +std::vector generateDrivableLanes(const lanelet::ConstLanelets & lanelets); std::vector generateDrivableLanesWithShoulderLanes( const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & shoulder_lanes); @@ -38,12 +56,36 @@ std::vector generateDrivableLanesWithShoulderLanes( std::vector getNonOverlappingExpandedLanes( PathWithLaneId & path, const std::vector & lanes, const DrivableAreaExpansionParameters & parameters); + +/** + * @brief generate the drivable area of the given path + * @param [inout] path path whose center line is used to calculate the drivable area and whose + * left/right bound are generated + * @param [in] lanes lanes driven by the ego vehicle + * @param [in] enable_expanding_hatched_road_markings if true, expand the drivable area into hatched + * road markings + * @param [in] enable_expanding_intersection_areas if true, expand the drivable area into + * intersection areas + * @param [in] enable_expanding_freespace_areas if true, expand the drivable area into freespace + * areas + * @param [in] planner_data planner data with the route handler (and map), the parameters, the ego + * pose, etc + * @param [in] is_driving_forward true if the ego vehicle drives in the forward direction + */ void generateDrivableArea( PathWithLaneId & path, const std::vector & lanes, const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas, const bool enable_expanding_freespace_areas, const std::shared_ptr planner_data, const bool is_driving_forward = true); +/** + * @brief generate the drivable area of the given path by applying the given offsets to its points + * @param [inout] path path whose center line is used to calculate the drivable area and whose + * left/right bound are generated + * @param [in] vehicle_length [m] length of the ego vehicle + * @param [in] offset [m] lateral offset between the path points and the drivable area + * @param [in] is_driving_forward true if the ego vehicle drives in the forward direction + */ void generateDrivableArea( PathWithLaneId & path, const double vehicle_length, const double offset, const bool is_driving_forward = true); @@ -72,6 +114,14 @@ std::vector getBoundWithHatchedRoadMarkings( const std::vector & original_bound, const std::shared_ptr & route_handler); +/** + * @brief Expand the given bound to include intersection areas from the map + * @param [in] original_bound original bound to expand + * @param [in] drivable_lanes lanelets to consider + * @param [in] route_handler route handler with the map information + * @param [in] is_left whether the bound to calculate is on the left or not + * @return the bound including intersection areas + */ std::vector getBoundWithIntersectionAreas( const std::vector & original_bound, const std::shared_ptr & route_handler, @@ -90,6 +140,12 @@ std::vector postProcess( const std::vector & drivable_lanes, const bool is_left, const bool is_driving_forward = true); +/** + * @brief combine two drivable area info objects + * @param [in] drivable_area_Info1 first drivable area info + * @param [in] drivable_area_Info2 second drivable area info + * @return the combined drivable area info + */ DrivableAreaInfo combineDrivableAreaInfo( const DrivableAreaInfo & drivable_area_info1, const DrivableAreaInfo & drivable_area_info2); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 9c35032e51063..012c42a379c00 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -626,8 +626,6 @@ std::vector updateBoundary( namespace autoware::behavior_path_planner::utils { -using autoware::universe_utils::Point2d; - std::optional getOverlappedLaneletId(const std::vector & lanes) { auto overlaps = [](const DrivableLanes & lanes, const DrivableLanes & target_lanes) { @@ -745,12 +743,12 @@ std::vector cutOverlappedLanes( return shorten_lanes; } -std::vector generateDrivableLanes(const lanelet::ConstLanelets & lanes) +std::vector generateDrivableLanes(const lanelet::ConstLanelets & lanelets) { - std::vector drivable_lanes(lanes.size()); - for (size_t i = 0; i < lanes.size(); ++i) { - drivable_lanes.at(i).left_lane = lanes.at(i); - drivable_lanes.at(i).right_lane = lanes.at(i); + std::vector drivable_lanes(lanelets.size()); + for (size_t i = 0; i < lanelets.size(); ++i) { + drivable_lanes.at(i).left_lane = lanelets.at(i); + drivable_lanes.at(i).right_lane = lanelets.at(i); } return drivable_lanes; } @@ -856,6 +854,9 @@ void generateDrivableArea( } } } + if (resampled_path.points.empty()) { + return; + } // add last point of path if enough far from the one of resampled path constexpr double th_last_point_distance = 0.3; if ( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_static_drivable_area.cpp new file mode 100644 index 0000000000000..ba3141a89b26a --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_static_drivable_area.cpp @@ -0,0 +1,528 @@ +// 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/behavior_path_planner_common/data_manager.hpp" +#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" + +#include +#include + +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +const auto intersection_map = + autoware::test_utils::make_map_bin_msg(autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_test_utils", "intersection/lanelet2_map.osm")); + +using autoware::behavior_path_planner::DrivableLanes; +using autoware::test_utils::make_lanelet; + +DrivableLanes make_drivable_lanes(const lanelet::ConstLanelet & ll) +{ + using autoware::behavior_path_planner::utils::generateDrivableLanes; + return generateDrivableLanes({ll}).front(); +} + +bool equal(const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2) +{ + return p1.x == p2.x && p1.y == p2.y && p1.z == p2.z; +} + +bool equal(const DrivableLanes & l1, const DrivableLanes & l2) +{ + if (l1.middle_lanes.size() != l2.middle_lanes.size()) { + return false; + } + auto are_equal = true; + are_equal &= boost::geometry::equals( + l1.left_lane.polygon2d().basicPolygon(), l2.left_lane.polygon2d().basicPolygon()); + are_equal &= boost::geometry::equals( + l1.right_lane.polygon2d().basicPolygon(), l2.right_lane.polygon2d().basicPolygon()); + for (auto i = 0UL; i < l1.middle_lanes.size(); ++i) { + are_equal &= boost::geometry::equals( + l1.middle_lanes[i].polygon2d().basicPolygon(), l2.middle_lanes[i].polygon2d().basicPolygon()); + } + return are_equal; +} + +TEST(StaticDrivableArea, getOverlappedLaneletId) +{ + using autoware::behavior_path_planner::utils::getOverlappedLaneletId; + + std::vector lanes; + { // empty lanes + const auto result = getOverlappedLaneletId(lanes); + EXPECT_FALSE(result.has_value()); + } + { // lanes at 0 + const DrivableLanes l = + make_drivable_lanes(make_lanelet({0.0, 1.0}, {5.0, 1.0}, {5.0, -1.0}, {5.0, -1.0})); + lanes.push_back(l); + const auto result = getOverlappedLaneletId(lanes); + EXPECT_FALSE(result.has_value()); + } + { // lanes at 1, overlap with 0 but ignored since it is the following lane + const DrivableLanes l = + make_drivable_lanes(make_lanelet({4.0, 1.0}, {8.0, 1.0}, {4.0, -1.0}, {8.0, -1.0})); + lanes.push_back(l); + const auto result = getOverlappedLaneletId(lanes); + EXPECT_FALSE(result.has_value()); + } + { // lanes at 2, overlap with 1 but ignored since it is the following lane + const DrivableLanes l = + make_drivable_lanes(make_lanelet({6.0, 1.0}, {10.0, 1.0}, {6.0, -1.0}, {10.0, -1.0})); + lanes.push_back(l); + const auto result = getOverlappedLaneletId(lanes); + EXPECT_FALSE(result.has_value()); + } + { // lanes at 3, overlap with 1 so 3 is returned + const DrivableLanes l = + make_drivable_lanes(make_lanelet({5.0, 0.0}, {5.0, 5.0}, {6.0, 0.0}, {6.0, 5.0})); + lanes.push_back(l); + const auto result = getOverlappedLaneletId(lanes); + ASSERT_TRUE(result.has_value()); + EXPECT_EQ(*result, 3UL); + } + { // lanes at 4, overlap with 2 but since 3 overlaps first it is still returned + const DrivableLanes l = + make_drivable_lanes(make_lanelet({7.0, 0.0}, {7.0, 5.0}, {8.0, 0.0}, {8.0, 5.0})); + lanes.push_back(l); + const auto result = getOverlappedLaneletId(lanes); + ASSERT_TRUE(result.has_value()); + EXPECT_EQ(*result, 3UL); + } + { // change 1 to no longer overlap with 3 and now 4 is the first overlap + const DrivableLanes l = make_drivable_lanes( + make_lanelet({100.0, 110.0}, {110.0, 100.0}, {100.0, 90.0}, {100.0, 90.0})); + lanes[1] = l; + const auto result = getOverlappedLaneletId(lanes); + ASSERT_TRUE(result.has_value()); + EXPECT_EQ(*result, 4UL); + } +} + +TEST(StaticDrivableArea, cutOverlappedLanes) +{ + using autoware::behavior_path_planner::utils::cutOverlappedLanes; + tier4_planning_msgs::msg::PathWithLaneId path; + std::vector lanes; + { // empty inputs + const auto result = cutOverlappedLanes(path, lanes); + EXPECT_TRUE(result.empty()); + EXPECT_TRUE(path.points.empty()); + } + constexpr auto path_size = 10UL; + const auto reset_path = [&]() { + path.points.clear(); + for (auto i = 0UL; i < path_size; ++i) { + path.points.emplace_back(); + path.points.back().point.pose.position.x = static_cast(i) * 1.0; + path.points.back().point.pose.position.y = 0.0; + } + }; + { // add some path points + reset_path(); + const auto result = cutOverlappedLanes(path, lanes); + EXPECT_TRUE(result.empty()); + ASSERT_EQ(path.points.size(), path_size); + for (auto i = 0UL; i < path_size; ++i) { + EXPECT_DOUBLE_EQ(path.points[i].point.pose.position.x, i * 1.0); + EXPECT_DOUBLE_EQ(path.points[i].point.pose.position.y, 0.0); + } + } + { // add some drivable lanes without any overlap (no overlap -> path is not modified) + reset_path(); + lanes.push_back( + make_drivable_lanes(make_lanelet({0.0, 1.0}, {2.0, 1.0}, {0.0, -1.0}, {2.0, -1.0}))); + const auto result = cutOverlappedLanes(path, lanes); + ASSERT_EQ(result.size(), lanes.size()); + EXPECT_TRUE(equal(result.front(), lanes.front())); + ASSERT_EQ(path.points.size(), path_size); + for (auto i = 0UL; i < path_size; ++i) { + EXPECT_DOUBLE_EQ(path.points[i].point.pose.position.x, i * 1.0); + EXPECT_DOUBLE_EQ(path.points[i].point.pose.position.y, 0.0); + } + } + { // add more drivable lanes without an overlap (no overlap -> path is not modified) + reset_path(); + lanes.push_back( + make_drivable_lanes(make_lanelet({2.0, 1.0}, {4.0, 1.0}, {2.0, -1.0}, {4.0, -1.0}))); + lanes.push_back( + make_drivable_lanes(make_lanelet({4.0, 1.0}, {6.0, 1.0}, {4.0, -1.0}, {6.0, -1.0}))); + const auto result = cutOverlappedLanes(path, lanes); + ASSERT_EQ(result.size(), lanes.size()); + for (auto i = 0UL; i < result.size(); ++i) { + EXPECT_TRUE(equal(result[i], lanes[i])); + } + ASSERT_EQ(path.points.size(), path_size); + for (auto i = 0UL; i < path_size; ++i) { + EXPECT_DOUBLE_EQ(path.points[i].point.pose.position.x, i * 1.0); + EXPECT_DOUBLE_EQ(path.points[i].point.pose.position.y, 0.0); + } + } + { // add an overlapping lane + reset_path(); + lanes.push_back( + make_drivable_lanes(make_lanelet({2.5, -1.0}, {2.5, 1.0}, {3.5, -1.0}, {3.5, 1.0}))); + const auto result = cutOverlappedLanes(path, lanes); + // the last lane is cut + ASSERT_EQ(result.size() + 1, lanes.size()); + for (auto i = 0UL; i < result.size(); ++i) { + EXPECT_TRUE(equal(result[i], lanes[i])); + } + // since the path points do not have ids, all points are cut + EXPECT_TRUE(path.points.empty()); + } + { // add the overlapping lane id to the path points + reset_path(); + for (auto & p : path.points) { + p.lane_ids.push_back(lanes.back().left_lane.id()); + } + cutOverlappedLanes(path, lanes); + // since the overlapped lane was removed, the path points were still cut + EXPECT_TRUE(path.points.empty()); + } + { // add the first lane id to some path points, only these points will be kept + reset_path(); + constexpr auto filtered_start = 3UL; + constexpr auto filtered_size = 5UL; + for (auto i = filtered_start; i < filtered_start + filtered_size; ++i) { + path.points[i].lane_ids.push_back(lanes.front().left_lane.id()); + } + cutOverlappedLanes(path, lanes); + ASSERT_EQ(path.points.size(), filtered_size); + for (auto i = 0UL; i < filtered_size; ++i) { + EXPECT_DOUBLE_EQ(path.points[i].point.pose.position.x, (i + filtered_start) * 1.0); + EXPECT_DOUBLE_EQ(path.points[i].point.pose.position.y, 0.0); + } + } +} + +TEST(StaticDrivableArea, generateDrivableLanes) +{ + using autoware::behavior_path_planner::utils::generateDrivableLanes; + lanelet::ConstLanelets lanelets; + lanelet::Lanelet ll; + { // empty case + const auto lanes = generateDrivableLanes(lanelets); + EXPECT_TRUE(lanes.empty()); + } + { // single lanelet: it is found in the drivable lane's left/right lanes + ll.setId(0); + lanelets.push_back(ll); + const auto lanes = generateDrivableLanes(lanelets); + ASSERT_EQ(lanes.size(), lanelets.size()); + EXPECT_TRUE(lanes[0].middle_lanes.empty()); + EXPECT_EQ(lanes[0].left_lane.id(), lanelets[0].id()); + EXPECT_EQ(lanes[0].right_lane.id(), lanelets[0].id()); + } + { // many lanelets: they are all in the calculated drivable lane + for (auto i = 1; i < 20; ++i) { + ll.setId(0); + lanelets.push_back(ll); + } + const auto lanes = generateDrivableLanes(lanelets); + ASSERT_EQ(lanes.size(), lanelets.size()); + for (auto i = 0UL; i < lanes.size(); ++i) { + EXPECT_TRUE(lanes[i].middle_lanes.empty()); + EXPECT_EQ(lanes[i].left_lane.id(), lanelets[i].id()); + EXPECT_EQ(lanes[i].right_lane.id(), lanelets[i].id()); + } + } +} + +TEST(StaticDrivableArea, generateDrivableArea_subfunction) +{ + using autoware::behavior_path_planner::utils::generateDrivableArea; + tier4_planning_msgs::msg::PathWithLaneId path; + tier4_planning_msgs::msg::PathPointWithLaneId p; + generateDrivableArea(path, 0.0, 0.0, true); + EXPECT_TRUE(path.left_bound.empty()); + EXPECT_TRUE(path.right_bound.empty()); + // add only 1 point : drivable area with 1 point + p.point.pose.position.set__x(0.0).set__y(0.0); + path.points.push_back(p); + auto lon_offset = 0.0; + auto lat_offset = 0.0; + generateDrivableArea(path, lon_offset, lat_offset, true); + // 3 points in the resulting drivable area: 1 for the path point and 2 for front/rear offset + ASSERT_EQ(path.left_bound.size(), 3UL); + ASSERT_EQ(path.right_bound.size(), 3UL); + // no offset so we expect exactly the same points + for (auto i = 0UL; i < 3UL; ++i) { + EXPECT_TRUE(equal(path.points.front().point.pose.position, path.left_bound[i])); + EXPECT_TRUE(equal(path.points.front().point.pose.position, path.right_bound[i])); + } + // add some offset + lon_offset = 1.0; + lat_offset = 0.5; + generateDrivableArea(path, lon_offset, lat_offset, true); + ASSERT_EQ(path.left_bound.size(), 3UL); + ASSERT_EQ(path.right_bound.size(), 3UL); + EXPECT_DOUBLE_EQ(path.left_bound[0].x, -lon_offset); + EXPECT_DOUBLE_EQ(path.left_bound[1].x, 0.0); + EXPECT_DOUBLE_EQ(path.left_bound[2].x, lon_offset); + EXPECT_DOUBLE_EQ(path.right_bound[0].x, -lon_offset); + EXPECT_DOUBLE_EQ(path.right_bound[1].x, 0.0); + EXPECT_DOUBLE_EQ(path.right_bound[2].x, lon_offset); + EXPECT_DOUBLE_EQ(path.left_bound[0].y, lat_offset); + EXPECT_DOUBLE_EQ(path.left_bound[1].y, lat_offset); + EXPECT_DOUBLE_EQ(path.left_bound[2].y, lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound[0].y, -lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound[1].y, -lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound[2].y, -lat_offset); + // set driving_forward to false: longitudinal offset is inversely applied + generateDrivableArea(path, lon_offset, lat_offset, false); + ASSERT_EQ(path.left_bound.size(), 3UL); + ASSERT_EQ(path.right_bound.size(), 3UL); + EXPECT_DOUBLE_EQ(path.left_bound[0].x, lon_offset); + EXPECT_DOUBLE_EQ(path.left_bound[1].x, 0.0); + EXPECT_DOUBLE_EQ(path.left_bound[2].x, -lon_offset); + EXPECT_DOUBLE_EQ(path.right_bound[0].x, lon_offset); + EXPECT_DOUBLE_EQ(path.right_bound[1].x, 0.0); + EXPECT_DOUBLE_EQ(path.right_bound[2].x, -lon_offset); + EXPECT_DOUBLE_EQ(path.left_bound[0].y, lat_offset); + EXPECT_DOUBLE_EQ(path.left_bound[1].y, lat_offset); + EXPECT_DOUBLE_EQ(path.left_bound[2].y, lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound[0].y, -lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound[1].y, -lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound[2].y, -lat_offset); + // add more points + for (auto x = 1; x < 10; ++x) { + // space points by more than 2m to avoid resampling + p.point.pose.position.set__x(x * 3.0).set__y(0.0); + path.points.push_back(p); + } + generateDrivableArea(path, lon_offset, lat_offset, true); + ASSERT_EQ(path.left_bound.size(), path.points.size() + 2UL); + ASSERT_EQ(path.right_bound.size(), path.points.size() + 2UL); + EXPECT_DOUBLE_EQ(path.left_bound.front().x, -lon_offset); + EXPECT_DOUBLE_EQ(path.right_bound.front().x, -lon_offset); + EXPECT_DOUBLE_EQ(path.left_bound.back().x, path.points.back().point.pose.position.x + lon_offset); + EXPECT_DOUBLE_EQ( + path.right_bound.back().x, path.points.back().point.pose.position.x + lon_offset); + EXPECT_DOUBLE_EQ(path.left_bound.front().y, lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound.front().y, -lat_offset); + EXPECT_DOUBLE_EQ(path.left_bound.back().y, lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound.back().y, -lat_offset); + for (auto i = 1UL; i + 1 < path.points.size(); ++i) { + const auto & path_p = path.points[i - 1].point.pose.position; + EXPECT_DOUBLE_EQ(path.left_bound[i].x, path_p.x); + EXPECT_DOUBLE_EQ(path.right_bound[i].x, path_p.x); + EXPECT_DOUBLE_EQ(path.left_bound[i].y, path_p.y + lat_offset); + EXPECT_DOUBLE_EQ(path.right_bound[i].y, path_p.y - lat_offset); + } + // case with self intersections + path.points.clear(); + p.point.pose.position.set__x(0.0).set__y(0.0); + path.points.push_back(p); + p.point.pose.position.set__x(3.0).set__y(0.0); + path.points.push_back(p); + p.point.pose.position.set__x(0.0).set__y(3.0); + path.points.push_back(p); + lon_offset = 0.0; + lat_offset = 3.0; + generateDrivableArea(path, lon_offset, lat_offset, false); + // TODO(Anyone): self intersection case looks buggy + ASSERT_EQ(path.left_bound.size(), path.points.size() + 2UL); + ASSERT_EQ(path.right_bound.size(), path.points.size() + 2UL); + EXPECT_TRUE(equal(path.left_bound[0], path.left_bound[1])); + EXPECT_TRUE(equal(path.right_bound[0], path.right_bound[1])); + EXPECT_TRUE(equal(path.left_bound[3], path.left_bound[4])); + EXPECT_TRUE(equal(path.right_bound[3], path.right_bound[4])); + EXPECT_DOUBLE_EQ(path.left_bound[1].x, 0.0); + EXPECT_DOUBLE_EQ(path.left_bound[1].y, 3.0); + EXPECT_DOUBLE_EQ(path.left_bound[2].x, 3.0); + EXPECT_DOUBLE_EQ(path.left_bound[2].y, 3.0); + EXPECT_DOUBLE_EQ(path.left_bound[3].x, 0.0); + EXPECT_DOUBLE_EQ(path.left_bound[3].y, 6.0); + EXPECT_DOUBLE_EQ(path.right_bound[1].x, 0.0); + EXPECT_DOUBLE_EQ(path.right_bound[1].y, -3.0); + EXPECT_DOUBLE_EQ(path.right_bound[2].x, 3.0); + EXPECT_DOUBLE_EQ(path.right_bound[2].y, -3.0); + EXPECT_DOUBLE_EQ(path.right_bound[3].x, 0.0); + EXPECT_DOUBLE_EQ(path.right_bound[3].y, 0.0); +} + +TEST(StaticDrivableArea, getBoundWithIntersectionAreas) +{ + using autoware::behavior_path_planner::utils::getBoundWithIntersectionAreas; + std::vector original_bound; + std::shared_ptr route_handler = + std::make_shared(); + std::vector drivable_lanes; + bool is_left = false; + auto result = + getBoundWithIntersectionAreas(original_bound, route_handler, drivable_lanes, is_left); + EXPECT_TRUE(result.empty()); + + route_handler->setMap(intersection_map); + DrivableLanes lanes; + const auto lanelet_with_intersection_area = route_handler->getLaneletsFromId(3101); + lanes.middle_lanes = {}; + lanes.right_lane = lanelet_with_intersection_area; + lanes.left_lane = lanelet_with_intersection_area; + for (const auto & p : lanelet_with_intersection_area.rightBound()) { + original_bound.push_back(p); + } + drivable_lanes.push_back(lanes); + result = getBoundWithIntersectionAreas(original_bound, route_handler, drivable_lanes, is_left); + // the expanded bound includes the intersection area so its size is larger + EXPECT_GT(result.size(), original_bound.size()); +} + +TEST(StaticDrivableArea, combineDrivableAreaInfo) +{ + using autoware::behavior_path_planner::utils::combineDrivableAreaInfo; + autoware::behavior_path_planner::DrivableAreaInfo drivable_area_info1; + autoware::behavior_path_planner::DrivableAreaInfo drivable_area_info2; + { + const auto combined = combineDrivableAreaInfo(drivable_area_info1, drivable_area_info2); + EXPECT_TRUE(combined.drivable_lanes.empty()); + } + { // combination of obstacles + drivable_area_info1.obstacles.emplace_back().pose.position.x = 1.0; + drivable_area_info2.obstacles.emplace_back().pose.position.x = 2.0; + const auto combined = combineDrivableAreaInfo(drivable_area_info1, drivable_area_info2); + ASSERT_EQ(combined.obstacles.size(), 2UL); + EXPECT_DOUBLE_EQ(combined.obstacles[0].pose.position.x, 1.0); + EXPECT_DOUBLE_EQ(combined.obstacles[1].pose.position.x, 2.0); + } + { // combination of the drivable lanes + DrivableLanes lanes; + lanes.middle_lanes.push_back(lanelet::Lanelet(0)); + lanes.middle_lanes.push_back(lanelet::Lanelet(1)); + drivable_area_info1.drivable_lanes.push_back(lanes); + lanes.middle_lanes.clear(); + lanes.middle_lanes.push_back(lanelet::Lanelet(2)); + lanes.middle_lanes.push_back(lanelet::Lanelet(3)); + drivable_area_info2.drivable_lanes.push_back(lanes); + const auto combined = combineDrivableAreaInfo(drivable_area_info1, drivable_area_info2); + ASSERT_EQ(combined.drivable_lanes.size(), 1UL); + ASSERT_EQ(combined.drivable_lanes[0].middle_lanes.size(), 4UL); + for (auto id = 0UL; id < combined.drivable_lanes[0].middle_lanes.size(); ++id) { + EXPECT_EQ(combined.drivable_lanes[0].middle_lanes[id].id(), id); + } + } + { // combination of the parameters + drivable_area_info1.drivable_margin = 5.0; + drivable_area_info2.drivable_margin = 2.0; + drivable_area_info1.enable_expanding_freespace_areas = false; + drivable_area_info2.enable_expanding_freespace_areas = false; + drivable_area_info1.enable_expanding_intersection_areas = true; + drivable_area_info2.enable_expanding_intersection_areas = true; + drivable_area_info1.enable_expanding_hatched_road_markings = false; + drivable_area_info2.enable_expanding_hatched_road_markings = true; + const auto combined = combineDrivableAreaInfo(drivable_area_info1, drivable_area_info2); + EXPECT_DOUBLE_EQ(combined.drivable_margin, 5.0); // expect the maximum of the margins + // expect OR of the booleans + EXPECT_FALSE(combined.enable_expanding_freespace_areas); + EXPECT_TRUE(combined.enable_expanding_intersection_areas); + EXPECT_TRUE(combined.enable_expanding_hatched_road_markings); + } +} + +TEST(DISABLED_StaticDrivableArea, generateDrivableArea) +{ + using autoware::behavior_path_planner::PlannerData; + using autoware::behavior_path_planner::utils::generateDrivableArea; + tier4_planning_msgs::msg::PathWithLaneId path; + std::vector lanes; + bool enable_expanding_hatched_road_markings = true; + bool enable_expanding_intersection_areas = true; + bool enable_expanding_freespace_areas = true; + bool is_driving_forward = true; + PlannerData planner_data; + planner_data.drivable_area_expansion_parameters.enabled = false; // disable dynamic expansion + planner_data.parameters.ego_nearest_dist_threshold = 1.0; + planner_data.parameters.ego_nearest_yaw_threshold = M_PI; + auto planner_data_ptr = std::make_shared(planner_data); + // empty: no crash + EXPECT_NO_FATAL_FAILURE(generateDrivableArea( + path, lanes, enable_expanding_hatched_road_markings, enable_expanding_intersection_areas, + enable_expanding_freespace_areas, planner_data_ptr, is_driving_forward)); + planner_data.route_handler = std::make_shared(); + planner_data.route_handler->setMap(intersection_map); + // create a path from a lanelet centerline + constexpr auto lanelet_id = 3008377; + const auto ll = planner_data.route_handler->getLaneletsFromId(lanelet_id); + const auto shoulder_ll = planner_data.route_handler->getLaneletsFromId(3008385); + lanes = autoware::behavior_path_planner::utils::generateDrivableLanes({ll, shoulder_ll}); + lanelet::BasicLineString2d path_ls; + for (const auto & p : ll.centerline().basicLineString()) { + tier4_planning_msgs::msg::PathPointWithLaneId pp; + pp.point.pose.position.x = p.x(); + pp.point.pose.position.y = p.y(); + pp.point.pose.position.z = p.z(); + pp.lane_ids = {lanelet_id}; + path.points.push_back(pp); + path_ls.emplace_back(p.x(), p.y()); + } + auto odometry = nav_msgs::msg::Odometry(); + odometry.pose.pose = path.points.front().point.pose; + planner_data.self_odometry = std::make_shared(odometry); + planner_data_ptr = std::make_shared(planner_data); + generateDrivableArea( + path, lanes, enable_expanding_hatched_road_markings, enable_expanding_intersection_areas, + enable_expanding_freespace_areas, planner_data_ptr, is_driving_forward); + + ASSERT_EQ(path.left_bound.size(), ll.leftBound().size()); + ASSERT_EQ(path.right_bound.size(), ll.rightBound().size()); + { + lanelet::BasicLineString2d left_ls; + lanelet::BasicLineString2d right_ls; + for (const auto & p : path.left_bound) { + left_ls.emplace_back(p.x, p.y); + } + for (const auto & p : path.right_bound) { + right_ls.emplace_back(p.x, p.y); + } + EXPECT_FALSE(boost::geometry::intersects(path_ls, left_ls)); + EXPECT_FALSE(boost::geometry::intersects(path_ls, right_ls)); // TODO(someone): this is failing + } + // reverse case + is_driving_forward = false; + odometry.pose.pose = std::prev(path.points.end(), 2)->point.pose; + planner_data.self_odometry = std::make_shared(odometry); + planner_data_ptr = std::make_shared(planner_data); + generateDrivableArea( + path, lanes, enable_expanding_hatched_road_markings, enable_expanding_intersection_areas, + enable_expanding_freespace_areas, planner_data_ptr, is_driving_forward); + ASSERT_EQ(path.left_bound.size(), ll.leftBound().size()); + ASSERT_EQ(path.right_bound.size(), ll.rightBound().size()); + { + lanelet::BasicLineString2d left_ls; + lanelet::BasicLineString2d right_ls; + for (const auto & p : path.left_bound) { + left_ls.emplace_back(p.x, p.y); + } + for (const auto & p : path.right_bound) { + right_ls.emplace_back(p.x, p.y); + } + EXPECT_FALSE(boost::geometry::intersects(path_ls, left_ls)); + EXPECT_FALSE(boost::geometry::intersects(path_ls, right_ls)); + } +} From fbf297afa91d394a32c9183fcef1c788269b778d Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Fri, 15 Nov 2024 15:44:39 +0900 Subject: [PATCH 015/273] chore(crosswalk)!: delete wide crosswalk corresponding function (#9329) Signed-off-by: Yuki Takagi --- .../src/manager.cpp | 2 -- .../src/scene_crosswalk.cpp | 4 +--- .../src/scene_crosswalk.hpp | 1 - 3 files changed, 1 insertion(+), 6 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp index 949a8de361409..8ba05be36ae56 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/manager.cpp @@ -51,8 +51,6 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".stop_position.stop_distance_from_object_preferred"); cp.stop_distance_from_object_limit = getOrDeclareParameter(node, ns + ".stop_position.stop_distance_from_object_limit"); - cp.far_object_threshold = - getOrDeclareParameter(node, ns + ".stop_position.far_object_threshold"); cp.stop_position_threshold = getOrDeclareParameter(node, ns + ".stop_position.stop_position_threshold"); cp.min_acc_preferred = diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 057c9d103aeba..51a0b4aa23fde 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -420,9 +420,7 @@ std::optional CrosswalkModule::calcStopPose( if (!ped_stop_pref_opt.has_value()) { RCLCPP_INFO(logger_, "Failure to calculate pref_stop."); return std::nullopt; - } else if ( - default_stop_opt.has_value() && ped_stop_pref_opt->dist > default_stop_opt->dist && - ped_stop_pref_opt->dist < default_stop_opt->dist + planner_param_.far_object_threshold) { + } else if (default_stop_opt.has_value() && ped_stop_pref_opt->dist > default_stop_opt->dist) { return default_stop_opt; } else { return ped_stop_pref_opt; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index 80f348027e1fd..de696aa670ad3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -122,7 +122,6 @@ class CrosswalkModule : public SceneModuleInterface double stop_distance_from_object_preferred; double stop_distance_from_object_limit; double stop_distance_from_crosswalk; - double far_object_threshold; double stop_position_threshold; double min_acc_preferred; double min_jerk_preferred; From 8028e382c2f1d6042488b6c7a832e42a5f4c29c5 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 15 Nov 2024 16:52:57 +0900 Subject: [PATCH 016/273] chore(autoware_behavior_velocity_intersection_module): include opencv as system (#9330) Signed-off-by: Y.Hisaki --- .../CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt index 167c7182e8f05..38298694d76f9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt @@ -22,6 +22,10 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/debug.cpp ) +target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC + ${OpenCV_INCLUDE_DIRS} +) + target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBRARIES} ) From d819a661cc5822fdacd88d2ad726001b49c59f84 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Fri, 15 Nov 2024 17:21:46 +0900 Subject: [PATCH 017/273] refactor(bpp): rework steering factor interface (#9325) * refactor(bpp): rework steering factor interface Signed-off-by: satoshi-ota * refactor(soa): rework steering factor interface Signed-off-by: satoshi-ota * refactor(AbLC): rework steering factor interface Signed-off-by: satoshi-ota * refactor(doa): rework steering factor interface Signed-off-by: satoshi-ota * refactor(lc): rework steering factor interface Signed-off-by: satoshi-ota * refactor(gp): rework steering factor interface Signed-off-by: satoshi-ota * refactor(sp): rework steering factor interface Signed-off-by: satoshi-ota * refactor(sbp): rework steering factor interface Signed-off-by: satoshi-ota * refactor(ss): rework steering factor interface Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/interface.cpp | 4 +- .../src/interface.hpp | 3 +- .../src/manager.cpp | 2 +- .../manager.hpp | 2 +- .../scene.hpp | 3 +- .../src/scene.cpp | 5 +- .../src/manager.cpp | 4 +- .../goal_planner_module.hpp | 3 +- .../src/goal_planner_module.cpp | 10 ++-- .../src/manager.cpp | 2 +- .../interface.hpp | 1 - .../src/interface.cpp | 13 +++-- .../src/manager.cpp | 2 +- .../behavior_path_planner_node.hpp | 3 +- .../src/behavior_path_planner_node.cpp | 22 +++++++-- .../src/planner_manager.cpp | 3 +- .../interface/scene_module_interface.hpp | 22 ++++----- .../scene_module_manager_interface.hpp | 26 +++++++++- .../interface/steering_factor_interface.hpp | 31 ++++++------ .../scene_module_manager_interface.cpp | 8 +-- .../interface/steering_factor_interface.cpp | 49 ++++--------------- .../manager.hpp | 2 +- .../sampling_planner_module.hpp | 3 +- .../src/sampling_planner_module.cpp | 5 +- .../manager.hpp | 2 +- .../behavior_path_side_shift_module/scene.hpp | 3 +- .../src/scene.cpp | 5 +- .../manager.hpp | 2 +- .../start_planner_module.hpp | 3 +- .../src/start_planner_module.cpp | 26 +++++----- .../manager.hpp | 2 +- .../scene.hpp | 11 ++--- .../src/scene.cpp | 10 ++-- 33 files changed, 136 insertions(+), 156 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 1051a3460be3b..0e0b0fcf63933 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -31,15 +31,13 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface( const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr) + objects_of_interest_marker_interface_ptr_map) : LaneChangeInterface{ name, node, parameters, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, - steering_factor_interface_ptr, std::make_unique(parameters, avoidance_by_lane_change_parameters)} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp index 4d200411904b0..c7fbba34b1adb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.hpp @@ -40,8 +40,7 @@ class AvoidanceByLaneChangeInterface : public LaneChangeInterface const std::shared_ptr & avoidance_by_lane_change_parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr); + objects_of_interest_marker_interface_ptr_map); bool isExecutionRequested() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp index 28ff6c9e110d6..c54774a575332 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp @@ -190,7 +190,7 @@ SMIPtr AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); + objects_of_interest_marker_interface_ptr_map_); } } // namespace autoware::behavior_path_planner 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 c0d2cdbee5c04..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 @@ -42,7 +42,7 @@ class DynamicObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index d02648f4ccfd4..33d33119602f5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -350,8 +350,7 @@ class DynamicObstacleAvoidanceModule : public SceneModuleInterface std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr); + objects_of_interest_marker_interface_ptr_map); void updateModuleParams(const std::any & parameters) override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index 852a3fe0feedf..c162170ae5eb0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -329,9 +329,8 @@ DynamicObstacleAvoidanceModule::DynamicObstacleAvoidanceModule( std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{std::move(parameters)}, target_objects_manager_{TargetObjectsManager( parameters_->successive_num_to_entry_dynamic_avoidance_condition, diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp index 3c730e6d36376..c04914ed1c72b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp @@ -26,7 +26,7 @@ ExternalRequestLaneChangeRightModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, + objects_of_interest_marker_interface_ptr_map_, std::make_unique(parameters_, direction_)); } @@ -35,7 +35,7 @@ ExternalRequestLaneChangeLeftModuleManager::createNewSceneModuleInstance() { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, + objects_of_interest_marker_interface_ptr_map_, std::make_unique(parameters_, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 907bce430f46d..e8c82c0a4600b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -142,8 +142,7 @@ class GoalPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr); + objects_of_interest_marker_interface_ptr_map); ~GoalPlannerModule() { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 5147f938c18fa..f69a0fe2c0a41 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -63,9 +63,8 @@ GoalPlannerModule::GoalPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, thread_safe_data_{mutex_, clock_}, @@ -135,6 +134,8 @@ GoalPlannerModule::GoalPlannerModule( initializeSafetyCheckParameters(); } + steering_factor_interface_.init(PlanningBehavior::GOAL_PLANNER); + /** * NOTE: Add `universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);` to functions called * from the main thread only. @@ -1262,8 +1263,7 @@ void GoalPlannerModule::updateSteeringFactor( return SteeringFactor::STRAIGHT; }); - steering_factor_interface_ptr_->updateSteeringFactor( - pose, distance, PlanningBehavior::GOAL_PLANNER, steering_factor_direction, type, ""); + steering_factor_interface_.set(pose, distance, steering_factor_direction, type, ""); } void GoalPlannerModule::decideVelocity() 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 346e863934945..6bbc34a495080 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 @@ -31,7 +31,7 @@ std::unique_ptr GoalPlannerModuleManager::createNewSceneMo { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); + objects_of_interest_marker_interface_ptr_map_); } GoalPlannerParameters GoalPlannerModuleManager::initGoalPlannerParameters( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index fd9375c7e9f75..bd309dd35a260 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -52,7 +52,6 @@ class LaneChangeInterface : public SceneModuleInterface const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr, std::unique_ptr && module_type); LaneChangeInterface(const LaneChangeInterface &) = delete; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 8fb1459f62c98..4ff2a6cc52e63 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -38,15 +38,15 @@ LaneChangeInterface::LaneChangeInterface( const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr, std::unique_ptr && module_type) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{std::move(parameters)}, module_type_{std::move(module_type)}, prev_approved_path_{std::make_unique()} { module_type_->setTimeKeeper(getTimeKeeper()); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); + steering_factor_interface_.init(PlanningBehavior::LANE_CHANGE); } void LaneChangeInterface::processOnExit() @@ -422,10 +422,9 @@ void LaneChangeInterface::updateSteeringFactorPtr(const BehaviorModuleOutput & o const auto finish_distance = autoware::motion_utils::calcSignedArcLength( output.path.points, current_position, status.lane_change_path.info.shift_line.end.position); - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {status.lane_change_path.info.shift_line.start, status.lane_change_path.info.shift_line.end}, - {start_distance, finish_distance}, PlanningBehavior::LANE_CHANGE, steering_factor_direction, - SteeringFactor::TURNING, ""); + {start_distance, finish_distance}, steering_factor_direction, SteeringFactor::TURNING, ""); } void LaneChangeInterface::updateSteeringFactorPtr( @@ -438,9 +437,9 @@ void LaneChangeInterface::updateSteeringFactorPtr( return SteeringFactor::RIGHT; }); - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {selected_path.info.shift_line.start, selected_path.info.shift_line.end}, {output.start_distance_to_path_change, output.finish_distance_to_path_change}, - PlanningBehavior::LANE_CHANGE, steering_factor_direction, SteeringFactor::APPROACHING, ""); + steering_factor_direction, SteeringFactor::APPROACHING, ""); } } // namespace autoware::behavior_path_planner 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 04371e8ff3f37..10dba38645f39 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 @@ -310,7 +310,7 @@ std::unique_ptr LaneChangeModuleManager::createNewSceneMod { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_, + objects_of_interest_marker_interface_ptr_map_, std::make_unique(parameters_, LaneChangeModuleType::NORMAL, direction_)); } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp index 1965a0f909927..5085af0d143bf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp @@ -124,6 +124,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr modified_goal_publisher_; rclcpp::Publisher::SharedPtr stop_reason_publisher_; rclcpp::Publisher::SharedPtr reroute_availability_publisher_; + rclcpp::Publisher::SharedPtr pub_steering_factors_; rclcpp::TimerBase::SharedPtr timer_; std::map::SharedPtr> path_candidate_publishers_; @@ -138,7 +139,7 @@ class BehaviorPathPlannerNode : public rclcpp::Node std::shared_ptr planner_manager_; - std::unique_ptr steering_factor_interface_ptr_; + SteeringFactorInterface steering_factor_interface_; std::mutex mutex_pd_; // mutex for planner_data_ std::mutex mutex_manager_; // mutex for bt_manager_ or planner_manager_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp index d168361a19858..a2fffa0bb7a63 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp @@ -52,6 +52,8 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod modified_goal_publisher_ = create_publisher("~/output/modified_goal", durable_qos); stop_reason_publisher_ = create_publisher("~/output/stop_reasons", 1); + pub_steering_factors_ = + create_publisher("/planning/steering_factor/intersection", 1); reroute_availability_publisher_ = create_publisher("~/output/is_reroute_available", 1); debug_avoidance_msg_array_publisher_ = @@ -114,7 +116,7 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod turn_signal_search_time, turn_signal_intersection_angle_threshold_deg); } - steering_factor_interface_ptr_ = std::make_unique(this, "intersection"); + steering_factor_interface_.init(PlanningBehavior::INTERSECTION); // Start timer { @@ -473,13 +475,23 @@ void BehaviorPathPlannerNode::publish_steering_factor( const auto [intersection_pose, intersection_distance] = planner_data->turn_signal_decider.getIntersectionPoseAndDistance(); - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {intersection_pose, intersection_pose}, {intersection_distance, intersection_distance}, - PlanningBehavior::INTERSECTION, steering_factor_direction, SteeringFactor::TURNING, ""); + steering_factor_direction, SteeringFactor::TURNING, ""); } else { - steering_factor_interface_ptr_->clearSteeringFactors(); + steering_factor_interface_.reset(); } - steering_factor_interface_ptr_->publishSteeringFactor(get_clock()->now()); + + autoware_adapi_v1_msgs::msg::SteeringFactorArray steering_factor_array; + steering_factor_array.header.frame_id = "map"; + steering_factor_array.header.stamp = this->now(); + + const auto steering_factor = steering_factor_interface_.get(); + if (steering_factor.behavior != PlanningBehavior::UNKNOWN) { + steering_factor_array.factors.emplace_back(steering_factor); + } + + pub_steering_factors_->publish(steering_factor_array); } void BehaviorPathPlannerNode::publish_reroute_availability() const diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp index 6281988036635..29c2d60a30d9f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp @@ -177,6 +177,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da std::for_each(manager_ptrs_.begin(), manager_ptrs_.end(), [](const auto & m) { m->updateObserver(); m->publishRTCStatus(); + m->publishSteeringFactor(); }); generateCombinedDrivableArea(result_output.valid_output, data); @@ -750,8 +751,6 @@ BehaviorModuleOutput SubPlannerManager::run( module_ptr->updateCurrentState(); - module_ptr->publishSteeringFactor(); - module_ptr->publishObjectsOfInterestMarker(); processing_time_.at(module_ptr->name()) += stop_watch.toc(module_ptr->name(), true); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index f536b211da8a6..997009edf0f43 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -74,6 +74,7 @@ using tier4_rtc_msgs::msg::State; using unique_identifier_msgs::msg::UUID; using visualization_msgs::msg::MarkerArray; using PlanResult = PathWithLaneId::SharedPtr; +using autoware_adapi_v1_msgs::msg::PlanningBehavior; enum class ModuleStatus { IDLE = 0, @@ -90,15 +91,13 @@ class SceneModuleInterface const std::string & name, rclcpp::Node & node, std::unordered_map> rtc_interface_ptr_map, std::unordered_map> - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr) + objects_of_interest_marker_interface_ptr_map) : name_{name}, logger_{node.get_logger().get_child(name)}, clock_{node.get_clock()}, rtc_interface_ptr_map_(std::move(rtc_interface_ptr_map)), objects_of_interest_marker_interface_ptr_map_( std::move(objects_of_interest_marker_interface_ptr_map)), - steering_factor_interface_ptr_{steering_factor_interface_ptr}, time_keeper_(std::make_shared()) { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { @@ -189,7 +188,8 @@ class SceneModuleInterface clearWaitingApproval(); unlockNewModuleLaunch(); unlockOutputPath(); - steering_factor_interface_ptr_->clearSteeringFactors(); + + reset_factor(); stop_reason_ = StopReason(); @@ -205,14 +205,6 @@ class SceneModuleInterface } } - void publishSteeringFactor() - { - if (!steering_factor_interface_ptr_) { - return; - } - steering_factor_interface_ptr_->publishSteeringFactor(clock_->now()); - } - void lockRTCCommand() { for (const auto & [module_name, ptr] : rtc_interface_ptr_map_) { @@ -275,6 +267,10 @@ class SceneModuleInterface StopReason getStopReason() const { return stop_reason_; } + void reset_factor() { steering_factor_interface_.reset(); } + + auto get_steering_factor() const -> SteeringFactor { return steering_factor_interface_.get(); } + std::string name() const { return name_; } std::optional getStopPose() const @@ -631,7 +627,7 @@ class SceneModuleInterface std::unordered_map> objects_of_interest_marker_interface_ptr_map_; - std::shared_ptr steering_factor_interface_ptr_; + mutable SteeringFactorInterface steering_factor_interface_; mutable std::optional stop_pose_{std::nullopt}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 2020399531e7e..5b61ea8152367 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -23,6 +23,7 @@ #include #include +#include #include #include @@ -40,6 +41,7 @@ using autoware::motion_utils::createDeadLineVirtualWallMarker; using autoware::motion_utils::createSlowDownVirtualWallMarker; using autoware::motion_utils::createStopVirtualWallMarker; using autoware::universe_utils::toHexString; +using autoware_adapi_v1_msgs::msg::SteeringFactorArray; using unique_identifier_msgs::msg::UUID; using SceneModulePtr = std::shared_ptr; using SceneModuleObserver = std::weak_ptr; @@ -102,6 +104,26 @@ class SceneModuleManagerInterface } } + void publishSteeringFactor() + { + autoware_adapi_v1_msgs::msg::SteeringFactorArray steering_factor_array; + steering_factor_array.header.frame_id = "map"; + steering_factor_array.header.stamp = node_->now(); + + for (const auto & m : observers_) { + if (m.expired()) { + continue; + } + + const auto steering_factor = m.lock()->get_steering_factor(); + if (steering_factor.behavior != PlanningBehavior::UNKNOWN) { + steering_factor_array.factors.emplace_back(steering_factor); + } + } + + pub_steering_factors_->publish(steering_factor_array); + } + void publishVirtualWall() const { using autoware::universe_utils::appendMarkerArray; @@ -262,14 +284,14 @@ class SceneModuleManagerInterface rclcpp::Publisher::SharedPtr pub_drivable_lanes_; + rclcpp::Publisher::SharedPtr pub_steering_factors_; + rclcpp::Publisher::SharedPtr pub_processing_time_; std::string name_; std::shared_ptr planner_data_; - std::shared_ptr steering_factor_interface_ptr_; - std::vector observers_; std::unique_ptr idle_module_ptr_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp index 385eb2a8ad0ae..eb644dee05b32 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp @@ -17,7 +17,8 @@ #include -#include +#include +#include #include #include @@ -25,29 +26,27 @@ namespace steering_factor_interface { + +using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::SteeringFactor; -using autoware_adapi_v1_msgs::msg::SteeringFactorArray; +using SteeringFactorBehavior = SteeringFactor::_behavior_type; +using SteeringFactorStatus = SteeringFactor::_status_type; using geometry_msgs::msg::Pose; class SteeringFactorInterface { public: - SteeringFactorInterface(rclcpp::Node * node, const std::string & name); - void publishSteeringFactor(const rclcpp::Time & stamp); - void updateSteeringFactor( - const std::array & poses, const std::array distances, - const std::string & behavior, const uint16_t direction, const uint16_t status, - const std::string & detail); - void clearSteeringFactors(); - -private: - rclcpp::Logger getLogger() const; + [[nodiscard]] SteeringFactor get() const { return steering_factor_; } + void init(const SteeringFactorBehavior & behavior) { behavior_ = behavior; } + void reset() { steering_factor_.behavior = PlanningBehavior::UNKNOWN; } - rclcpp::Publisher::SharedPtr pub_steering_factors_; + void set( + const std::array & pose, const std::array distance, + const uint16_t direction, const uint16_t status, const std::string & detail = ""); - std::mutex mutex_; - rclcpp::Logger logger_; - SteeringFactorArray registered_steering_factors_; +private: + SteeringFactorBehavior behavior_{SteeringFactor::UNKNOWN}; + SteeringFactor steering_factor_{}; }; } // namespace steering_factor_interface diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp index 535e5cff43e33..35f29921b97b5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp @@ -57,12 +57,8 @@ void SceneModuleManagerInterface::initInterface( pub_drivable_lanes_ = node->create_publisher("~/drivable_lanes/" + name_, 20); pub_processing_time_ = node->create_publisher( "~/processing_time/" + name_, 20); - } - - // init steering factor - { - steering_factor_interface_ptr_ = - std::make_shared(node, utils::convertToSnakeCase(name_)); + pub_steering_factors_ = + node->create_publisher("/planning/steering_factor/" + name_, 1); } // misc diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/steering_factor_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/steering_factor_interface.cpp index daebfa31be311..8f39063b5a93b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/steering_factor_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/steering_factor_interface.cpp @@ -16,48 +16,17 @@ namespace steering_factor_interface { -SteeringFactorInterface::SteeringFactorInterface(rclcpp::Node * node, const std::string & name) -: logger_{node->get_logger().get_child("PlanningAPI[" + name + "]")} +void SteeringFactorInterface::set( + const std::array & pose, const std::array distance, const uint16_t direction, + const uint16_t status, const std::string & detail) { - // Publisher - pub_steering_factors_ = - node->create_publisher("/planning/steering_factor/" + name, 1); -} - -void SteeringFactorInterface::publishSteeringFactor(const rclcpp::Time & stamp) -{ - std::lock_guard lock(mutex_); - registered_steering_factors_.header.stamp = stamp; - pub_steering_factors_->publish(registered_steering_factors_); -} - -void SteeringFactorInterface::updateSteeringFactor( - const std::array & pose, const std::array distance, - const std::string & behavior, const uint16_t direction, const uint16_t status, - const std::string & detail) -{ - std::lock_guard lock(mutex_); - SteeringFactor factor; - factor.pose = pose; + steering_factor_.pose = pose; std::array converted_distance{0.0, 0.0}; for (int i = 0; i < 2; ++i) converted_distance[i] = static_cast(distance[i]); - factor.distance = converted_distance; - factor.behavior = behavior; - factor.direction = direction; - factor.status = status; - factor.detail = detail; - registered_steering_factors_.factors = {factor}; + steering_factor_.distance = converted_distance; + steering_factor_.behavior = behavior_; + steering_factor_.direction = direction; + steering_factor_.status = status; + steering_factor_.detail = detail; } - -void SteeringFactorInterface::clearSteeringFactors() -{ - std::lock_guard lock(mutex_); - registered_steering_factors_.factors.clear(); -} - -rclcpp::Logger SteeringFactorInterface::getLogger() const -{ - return logger_; -} - } // namespace steering_factor_interface diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp index 778afd1698ff2..28c310ae20ec2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/manager.hpp @@ -38,7 +38,7 @@ class SamplingPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams( diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp index d0d34b5d9a37f..e82c4fd287432 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -86,8 +86,7 @@ class SamplingPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr); + objects_of_interest_marker_interface_ptr_map); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index 1cf40255f4fef..ede912ea1c285 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -33,9 +33,8 @@ SamplingPlannerModule::SamplingPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()} { internal_params_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp index d1c9c8e2535ec..b495e6619a1c7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/manager.hpp @@ -39,7 +39,7 @@ class SideShiftModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp index 74953b7927b5d..543b17aca9352 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp @@ -45,8 +45,7 @@ class SideShiftModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr); + objects_of_interest_marker_interface_ptr_map); bool isExecutionRequested() const override; bool isExecutionReady() const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index e1f6d0bb6af9c..5970a3a807517 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -41,9 +41,8 @@ SideShiftModule::SideShiftModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters} { } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp index a26c48ad065c9..5d3d224673124 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/manager.hpp @@ -38,7 +38,7 @@ class StartPlannerModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index e0bb5d95f565a..bb70ae2638056 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -88,8 +88,7 @@ class StartPlannerModule : public SceneModuleInterface const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr); + objects_of_interest_marker_interface_ptr_map); ~StartPlannerModule() override { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index fa17409de5b94..b303ffb1c71d9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -58,9 +58,8 @@ StartPlannerModule::StartPlannerModule( const std::shared_ptr & parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT parameters_{parameters}, vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, is_freespace_planner_cb_running_{false} @@ -97,6 +96,8 @@ StartPlannerModule::StartPlannerModule( std::bind(&StartPlannerModule::onFreespacePlannerTimer, this), freespace_planner_timer_cb_group_); } + + steering_factor_interface_.init(PlanningBehavior::START_PLANNER); } void StartPlannerModule::onFreespacePlannerTimer() @@ -747,10 +748,9 @@ BehaviorModuleOutput StartPlannerModule::plan() path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.end_pose.position); updateRTCStatus(start_distance, finish_distance); - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, - {start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction, - SteeringFactor::TURNING, ""); + {start_distance, finish_distance}, steering_factor_direction, SteeringFactor::TURNING, ""); setDebugData(); return output; } @@ -758,9 +758,9 @@ BehaviorModuleOutput StartPlannerModule::plan() path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); updateRTCStatus(0.0, distance); - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance}, - PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::TURNING, ""); + steering_factor_direction, SteeringFactor::TURNING, ""); setDebugData(); @@ -853,10 +853,10 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.end_pose.position); updateRTCStatus(start_distance, finish_distance); - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, - {start_distance, finish_distance}, PlanningBehavior::START_PLANNER, steering_factor_direction, - SteeringFactor::APPROACHING, ""); + {start_distance, finish_distance}, steering_factor_direction, SteeringFactor::APPROACHING, + ""); setDebugData(); return output; @@ -865,9 +865,9 @@ BehaviorModuleOutput StartPlannerModule::planWaitingApproval() stop_path.points, planner_data_->self_odometry->pose.pose.position, status_.pull_out_path.start_pose.position); updateRTCStatus(0.0, distance); - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {status_.pull_out_path.start_pose, status_.pull_out_path.end_pose}, {0.0, distance}, - PlanningBehavior::START_PLANNER, steering_factor_direction, SteeringFactor::APPROACHING, ""); + steering_factor_direction, SteeringFactor::APPROACHING, ""); setDebugData(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp index fa54ec52203f9..895390f91cc16 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/manager.hpp @@ -41,7 +41,7 @@ class StaticObstacleAvoidanceModuleManager : public SceneModuleManagerInterface { return std::make_unique( name_, *node_, parameters_, rtc_interface_ptr_map_, - objects_of_interest_marker_interface_ptr_map_, steering_factor_interface_ptr_); + objects_of_interest_marker_interface_ptr_map_); } void updateModuleParams(const std::vector & parameters) override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index d4b7cae705a61..b700cafa3b2f4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -46,8 +46,7 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr); + objects_of_interest_marker_interface_ptr_map); CandidateOutput planCandidate() const override; BehaviorModuleOutput plan() override; @@ -130,9 +129,9 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface } if (finish_distance > -1.0e-03) { - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {left_shift.start_pose, left_shift.finish_pose}, {start_distance, finish_distance}, - PlanningBehavior::AVOIDANCE, SteeringFactor::LEFT, SteeringFactor::TURNING, ""); + SteeringFactor::LEFT, SteeringFactor::TURNING, ""); } } @@ -150,9 +149,9 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface } if (finish_distance > -1.0e-03) { - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {right_shift.start_pose, right_shift.finish_pose}, {start_distance, finish_distance}, - PlanningBehavior::AVOIDANCE, SteeringFactor::RIGHT, SteeringFactor::TURNING, ""); + SteeringFactor::RIGHT, SteeringFactor::TURNING, ""); } } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index f30e09fe6475f..d92e43dcf13bf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -77,13 +77,13 @@ StaticObstacleAvoidanceModule::StaticObstacleAvoidanceModule( const std::string & name, rclcpp::Node & node, std::shared_ptr parameters, const std::unordered_map> & rtc_interface_ptr_map, std::unordered_map> & - objects_of_interest_marker_interface_ptr_map, - std::shared_ptr & steering_factor_interface_ptr) -: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map, steering_factor_interface_ptr}, // NOLINT + objects_of_interest_marker_interface_ptr_map) +: SceneModuleInterface{name, node, rtc_interface_ptr_map, objects_of_interest_marker_interface_ptr_map}, // NOLINT helper_{std::make_shared(parameters)}, parameters_{parameters}, generator_{parameters} { + steering_factor_interface_.init(PlanningBehavior::AVOIDANCE); } bool StaticObstacleAvoidanceModule::isExecutionRequested() const @@ -1204,10 +1204,10 @@ CandidateOutput StaticObstacleAvoidanceModule::planCandidate() const const uint16_t steering_factor_direction = std::invoke([&output]() { return output.lateral_shift > 0.0 ? SteeringFactor::LEFT : SteeringFactor::RIGHT; }); - steering_factor_interface_ptr_->updateSteeringFactor( + steering_factor_interface_.set( {sl_front.start, sl_back.end}, {output.start_distance_to_path_change, output.finish_distance_to_path_change}, - PlanningBehavior::AVOIDANCE, steering_factor_direction, SteeringFactor::APPROACHING, ""); + steering_factor_direction, SteeringFactor::APPROACHING, ""); output.path_candidate = shifted_path.path; return output; From 8dfc04a3554155f52b39b4227c08ecb8800ecbf4 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 15 Nov 2024 18:29:12 +0900 Subject: [PATCH 018/273] fix(bpp): update collided polygon pose only once (#9338) * fix(bpp): update collided polygon pose only once Signed-off-by: Zulfaqar Azmi * add expected pose Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../path_safety_checker/safety_check.cpp | 29 +++++++++++-------- 1 file changed, 17 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index 5b629cf0c9a20..04b61b86dfa02 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -622,13 +622,15 @@ std::vector get_collided_polygons( // check intersects if (boost::geometry::intersects(ego_polygon, obj_polygon)) { - debug.unsafe_reason = "overlap_polygon"; + if (collided_polygons.empty()) { + debug.unsafe_reason = "overlap_polygon"; + debug.expected_ego_pose = ego_pose; + debug.expected_obj_pose = obj_pose; + debug.extended_ego_polygon = ego_polygon; + debug.extended_obj_polygon = obj_polygon; + } collided_polygons.push_back(obj_polygon); - debug.expected_ego_pose = ego_pose; - debug.expected_obj_pose = obj_pose; - debug.extended_ego_polygon = ego_polygon; - debug.extended_obj_polygon = obj_polygon; continue; } @@ -676,14 +678,17 @@ std::vector get_collided_polygons( // check intersects with extended polygon if (boost::geometry::intersects(extended_ego_polygon, extended_obj_polygon)) { - debug.unsafe_reason = "overlap_extended_polygon"; + if (collided_polygons.empty()) { + debug.unsafe_reason = "overlap_extended_polygon"; + debug.rss_longitudinal = rss_dist; + debug.inter_vehicle_distance = min_lon_length; + debug.expected_ego_pose = ego_pose; + debug.expected_obj_pose = obj_pose; + debug.extended_ego_polygon = extended_ego_polygon; + debug.extended_obj_polygon = extended_obj_polygon; + debug.is_front = is_object_front; + } collided_polygons.push_back(obj_polygon); - - debug.rss_longitudinal = rss_dist; - debug.inter_vehicle_distance = min_lon_length; - debug.extended_ego_polygon = extended_ego_polygon; - debug.extended_obj_polygon = extended_obj_polygon; - debug.is_front = is_object_front; } } From 1ed46dc475617f349883ca907814397b2156c994 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Fri, 15 Nov 2024 20:01:25 +0900 Subject: [PATCH 019/273] fix(static_obstacle_avoidance): override setInitState (#9340) override setInitState Signed-off-by: Go Sakayori --- .../behavior_path_static_obstacle_avoidance_module/scene.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp index b700cafa3b2f4..5848cc75f148e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/scene.hpp @@ -65,6 +65,8 @@ class StaticObstacleAvoidanceModule : public SceneModuleInterface std::shared_ptr get_debug_msg_array() const; private: + ModuleStatus setInitState() const override { return ModuleStatus::WAITING_APPROVAL; }; + /** * @brief return the result whether the module can stop path generation process. * @param avoidance data. From 08951b23a20e86f52fde0c1e9cdc6d5d31677c54 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Sun, 17 Nov 2024 17:18:40 +0900 Subject: [PATCH 020/273] chore(autoware_traffic_light_visualization): include opencv as system (#9331) Signed-off-by: Y.Hisaki --- .../autoware_traffic_light_visualization/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/perception/autoware_traffic_light_visualization/CMakeLists.txt b/perception/autoware_traffic_light_visualization/CMakeLists.txt index 4db2163e81932..f14f0e292b0ba 100644 --- a/perception/autoware_traffic_light_visualization/CMakeLists.txt +++ b/perception/autoware_traffic_light_visualization/CMakeLists.txt @@ -11,6 +11,10 @@ ament_auto_add_library(traffic_light_roi_visualizer SHARED src/traffic_light_roi_visualizer/shape_draw.cpp ) +target_include_directories(traffic_light_roi_visualizer SYSTEM PUBLIC + ${OpenCV_INCLUDE_DIRS} +) + target_link_libraries(traffic_light_roi_visualizer ${OpenCV_LIBRARIES} ) From 6f40830ee5eeb34eb88150a314308053a16ff77f Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Nov 2024 09:06:12 +0900 Subject: [PATCH 021/273] refactor(factor): move steering factor interface to motion utils (#9337) Signed-off-by: satoshi-ota --- .../factor}/steering_factor_interface.hpp | 15 ++++++--------- .../src/factor}/steering_factor_interface.cpp | 8 ++++---- .../behavior_path_planner_node.hpp | 4 ++-- .../CMakeLists.txt | 1 - .../interface/scene_module_interface.hpp | 8 +++----- .../interface/scene_module_manager_interface.hpp | 2 +- 6 files changed, 16 insertions(+), 22 deletions(-) rename {planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface => common/autoware_motion_utils/include/autoware/motion_utils/factor}/steering_factor_interface.hpp (78%) rename {planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface => common/autoware_motion_utils/src/factor}/steering_factor_interface.cpp (85%) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp b/common/autoware_motion_utils/include/autoware/motion_utils/factor/steering_factor_interface.hpp similarity index 78% rename from planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp rename to common/autoware_motion_utils/include/autoware/motion_utils/factor/steering_factor_interface.hpp index eb644dee05b32..5b701a73ac543 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp +++ b/common/autoware_motion_utils/include/autoware/motion_utils/factor/steering_factor_interface.hpp @@ -1,4 +1,4 @@ -// Copyright 2022 Tier IV, Inc. +// Copyright 2022 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. @@ -12,19 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__STEERING_FACTOR_INTERFACE_HPP_ -#define AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__STEERING_FACTOR_INTERFACE_HPP_ - -#include +#ifndef AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_ +#define AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_ #include #include #include -#include #include -namespace steering_factor_interface +namespace autoware::motion_utils { using autoware_adapi_v1_msgs::msg::PlanningBehavior; @@ -49,6 +46,6 @@ class SteeringFactorInterface SteeringFactor steering_factor_{}; }; -} // namespace steering_factor_interface +} // namespace autoware::motion_utils -#endif // AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__STEERING_FACTOR_INTERFACE_HPP_ +#endif // AUTOWARE__MOTION_UTILS__FACTOR__STEERING_FACTOR_INTERFACE_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/steering_factor_interface.cpp b/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp similarity index 85% rename from planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/steering_factor_interface.cpp rename to common/autoware_motion_utils/src/factor/steering_factor_interface.cpp index 8f39063b5a93b..f85b5b26cd0c2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/steering_factor_interface.cpp +++ b/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp @@ -1,4 +1,4 @@ -// Copyright 2022 Tier IV, Inc. +// Copyright 2022 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. @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp" +#include -namespace steering_factor_interface +namespace autoware::motion_utils { void SteeringFactorInterface::set( const std::array & pose, const std::array distance, const uint16_t direction, @@ -29,4 +29,4 @@ void SteeringFactorInterface::set( steering_factor_.status = status; steering_factor_.detail = detail; } -} // namespace steering_factor_interface +} // namespace autoware::motion_utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp index 5085af0d143bf..f0bd4486eb04a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp @@ -17,10 +17,10 @@ #include "autoware/behavior_path_planner_common/data_manager.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" -#include "autoware/behavior_path_planner_common/interface/steering_factor_interface.hpp" #include "autoware/universe_utils/ros/logger_level_configure.hpp" #include "planner_manager.hpp" +#include #include #include @@ -52,6 +52,7 @@ namespace autoware::behavior_path_planner { +using autoware::motion_utils::SteeringFactorInterface; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::PredictedObject; @@ -65,7 +66,6 @@ using autoware_vehicle_msgs::msg::TurnIndicatorsCommand; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; using rcl_interfaces::msg::SetParametersResult; -using steering_factor_interface::SteeringFactorInterface; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_planning_msgs::msg::LateralOffset; using tier4_planning_msgs::msg::PathWithLaneId; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt index 22faf1a6375d8..ac33966a1bf7c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt @@ -8,7 +8,6 @@ find_package(magic_enum CONFIG REQUIRED) ament_auto_add_library(${PROJECT_NAME} SHARED src/turn_signal_decider.cpp - src/interface/steering_factor_interface.cpp src/interface/scene_module_visitor.cpp src/interface/scene_module_interface.cpp src/interface/scene_module_manager_interface.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index 997009edf0f43..60a5faf6cd929 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -20,8 +20,8 @@ #include "autoware/behavior_path_planner_common/marker_utils/utils.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" -#include #include +#include #include #include #include @@ -35,8 +35,7 @@ #include #include -#include -#include +#include #include #include #include @@ -57,6 +56,7 @@ namespace autoware::behavior_path_planner { +using autoware::motion_utils::SteeringFactorInterface; using autoware::objects_of_interest_marker_interface::ColorName; using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using autoware::rtc_interface::RTCInterface; @@ -64,7 +64,6 @@ using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::generateUUID; using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::SteeringFactor; -using steering_factor_interface::SteeringFactorInterface; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_planning_msgs::msg::PathWithLaneId; using tier4_planning_msgs::msg::StopFactor; @@ -74,7 +73,6 @@ using tier4_rtc_msgs::msg::State; using unique_identifier_msgs::msg::UUID; using visualization_msgs::msg::MarkerArray; using PlanResult = PathWithLaneId::SharedPtr; -using autoware_adapi_v1_msgs::msg::PlanningBehavior; enum class ModuleStatus { IDLE = 0, diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 5b61ea8152367..65df5e15dad41 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -106,7 +106,7 @@ class SceneModuleManagerInterface void publishSteeringFactor() { - autoware_adapi_v1_msgs::msg::SteeringFactorArray steering_factor_array; + SteeringFactorArray steering_factor_array; steering_factor_array.header.frame_id = "map"; steering_factor_array.header.stamp = node_->now(); From a0c4ab45d78f64ef9c7c1022af2c8f61682ae32a Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Mon, 18 Nov 2024 09:39:46 +0900 Subject: [PATCH 022/273] refactor(lane_change): refactor extended object safety check (#9322) * refactor LC extended object collision check code Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --------- Signed-off-by: mohammad alqudah Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --- .../scene.hpp | 7 ++-- .../utils/utils.hpp | 5 +-- .../src/scene.cpp | 42 +++++++++++++------ .../src/utils/utils.cpp | 15 ++----- 4 files changed, 40 insertions(+), 29 deletions(-) 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 4c8cbe05f5535..dd21233c716f1 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 @@ -169,12 +169,13 @@ class NormalLaneChange : public LaneChangeBase bool has_collision_with_decel_patterns( const LaneChangePath & lane_change_path, const ExtendedPredictedObjects & objects, const size_t deceleration_sampling_num, const RSSparams & rss_param, - CollisionCheckDebugMap & debug_data) const; + const bool check_prepare_phase, CollisionCheckDebugMap & debug_data) const; bool is_collided( - const PathWithLaneId & lane_change_path, const ExtendedPredictedObject & obj, + const LaneChangePath & lane_change_path, const ExtendedPredictedObject & obj, const std::vector & ego_predicted_path, - const RSSparams & selected_rss_param, CollisionCheckDebugMap & debug_data) const; + const RSSparams & selected_rss_param, const bool check_prepare_phase, + CollisionCheckDebugMap & debug_data) const; double get_max_velocity_for_safety_check() const; 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 747a991b038e9..edf64ecdc49ee 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 @@ -145,7 +145,7 @@ lanelet::BasicPolygon2d create_polygon( ExtendedPredictedObject transform( const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase); + const LaneChangeParameters & lane_change_parameters); bool is_collided_polygons_in_lanelet( const std::vector & collided_polygons, const lanelet::BasicPolygon2d & lanes_polygon); @@ -249,8 +249,7 @@ bool is_before_terminal( double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, const Pose & pose); ExtendedPredictedObjects transform_to_extended_objects( - const CommonDataPtr & common_data_ptr, const std::vector & objects, - const bool check_prepare_phase); + const CommonDataPtr & common_data_ptr, const std::vector & objects); double get_distance_to_next_regulatory_element( const CommonDataPtr & common_data_ptr, const bool ignore_crosswalk = false, 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 1e102a8b7542d..3f06ff0481c7e 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 @@ -1006,17 +1006,16 @@ FilteredByLanesExtendedObjects NormalLaneChange::filterObjects() const return is_within_vel_th(object) && ahead_of_ego; }); - const auto is_check_prepare_phase = check_prepare_phase(); const auto target_lane_leading_extended_objects = utils::lane_change::transform_to_extended_objects( - common_data_ptr_, filtered_by_lanes_objects.target_lane_leading, is_check_prepare_phase); + common_data_ptr_, filtered_by_lanes_objects.target_lane_leading); const auto target_lane_trailing_extended_objects = utils::lane_change::transform_to_extended_objects( - common_data_ptr_, filtered_by_lanes_objects.target_lane_trailing, is_check_prepare_phase); + common_data_ptr_, filtered_by_lanes_objects.target_lane_trailing); const auto current_lane_extended_objects = utils::lane_change::transform_to_extended_objects( - common_data_ptr_, filtered_by_lanes_objects.current_lane, is_check_prepare_phase); + common_data_ptr_, filtered_by_lanes_objects.current_lane); const auto other_lane_extended_objects = utils::lane_change::transform_to_extended_objects( - common_data_ptr_, filtered_by_lanes_objects.other_lane, is_check_prepare_phase); + common_data_ptr_, filtered_by_lanes_objects.other_lane); FilteredByLanesExtendedObjects lane_change_target_objects( current_lane_extended_objects, target_lane_leading_extended_objects, @@ -1856,10 +1855,13 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( return {is_safe, !is_object_behind_ego}; } + const auto is_check_prepare_phase = check_prepare_phase(); + const auto all_decel_pattern_has_collision = [&](const utils::path_safety_checker::ExtendedPredictedObjects & objects) -> bool { return has_collision_with_decel_patterns( - lane_change_path, objects, deceleration_sampling_num, rss_params, debug_data); + lane_change_path, objects, deceleration_sampling_num, rss_params, is_check_prepare_phase, + debug_data); }; if (all_decel_pattern_has_collision(collision_check_objects.trailing)) { @@ -1876,7 +1878,7 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe( bool NormalLaneChange::has_collision_with_decel_patterns( const LaneChangePath & lane_change_path, const ExtendedPredictedObjects & objects, const size_t deceleration_sampling_num, const RSSparams & rss_param, - CollisionCheckDebugMap & debug_data) const + const bool check_prepare_phase, CollisionCheckDebugMap & debug_data) const { if (objects.empty()) { return false; @@ -1922,7 +1924,8 @@ bool NormalLaneChange::has_collision_with_decel_patterns( ? lane_change_parameters_->rss_params_for_parked : rss_param; return is_collided( - lane_change_path.path, obj, ego_predicted_path, selected_rss_param, debug_data); + lane_change_path, obj, ego_predicted_path, selected_rss_param, check_prepare_phase, + debug_data); }); }); @@ -1930,13 +1933,14 @@ bool NormalLaneChange::has_collision_with_decel_patterns( } bool NormalLaneChange::is_collided( - const PathWithLaneId & lane_change_path, const ExtendedPredictedObject & obj, + const LaneChangePath & lane_change_path, const ExtendedPredictedObject & obj, const std::vector & ego_predicted_path, - const RSSparams & selected_rss_param, CollisionCheckDebugMap & debug_data) const + const RSSparams & selected_rss_param, const bool check_prepare_phase, + CollisionCheckDebugMap & debug_data) const { constexpr auto is_collided{true}; - if (lane_change_path.points.empty()) { + if (lane_change_path.path.points.empty()) { return !is_collided; } @@ -1961,9 +1965,23 @@ bool NormalLaneChange::is_collided( const auto safety_check_max_vel = get_max_velocity_for_safety_check(); const auto & bpp_param = *common_data_ptr_->bpp_param_ptr; + const double velocity_threshold = lane_change_parameters_->stopped_object_velocity_threshold; + const double prepare_duration = lane_change_path.info.duration.prepare; + const double start_time = check_prepare_phase ? 0.0 : prepare_duration; + for (const auto & obj_path : obj_predicted_paths) { + utils::path_safety_checker::PredictedPathWithPolygon predicted_obj_path; + predicted_obj_path.confidence = obj_path.confidence; + std::copy_if( + obj_path.path.begin(), obj_path.path.end(), std::back_inserter(predicted_obj_path.path), + [&](const auto & entry) { + return !( + entry.time < start_time || + (entry.time < prepare_duration && entry.velocity < velocity_threshold)); + }); + const auto collided_polygons = utils::path_safety_checker::get_collided_polygons( - lane_change_path, ego_predicted_path, obj, obj_path, bpp_param.vehicle_info, + lane_change_path.path, ego_predicted_path, obj, predicted_obj_path, bpp_param.vehicle_info, selected_rss_param, hysteresis_factor, safety_check_max_vel, collision_check_yaw_diff_threshold, current_debug_data.second); 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 4d92b7440d1ec..69cf6441ef766 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 @@ -914,14 +914,11 @@ lanelet::BasicPolygon2d create_polygon( ExtendedPredictedObject transform( const PredictedObject & object, [[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase) + const LaneChangeParameters & lane_change_parameters) { ExtendedPredictedObject extended_object(object); const auto & time_resolution = lane_change_parameters.prediction_time_resolution; - const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration; - const auto & velocity_threshold = lane_change_parameters.stopped_object_velocity_threshold; - const auto start_time = check_at_prepare_phase ? 0.0 : prepare_duration; const double obj_vel_norm = std::hypot(extended_object.initial_twist.linear.x, extended_object.initial_twist.linear.y); @@ -933,11 +930,8 @@ ExtendedPredictedObject transform( extended_object.predicted_paths.at(i).confidence = path.confidence; // create path - for (double t = start_time; t < end_time + std::numeric_limits::epsilon(); + for (double t = 0.0; t < end_time + std::numeric_limits::epsilon(); t += time_resolution) { - if (t < prepare_duration && obj_vel_norm < velocity_threshold) { - continue; - } const auto obj_pose = autoware::object_recognition_utils::calcInterpolatedPose(path, t); if (obj_pose) { const auto obj_polygon = autoware::universe_utils::toPolygon2d(*obj_pose, object.shape); @@ -1163,8 +1157,7 @@ double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, co } ExtendedPredictedObjects transform_to_extended_objects( - const CommonDataPtr & common_data_ptr, const std::vector & objects, - const bool check_prepare_phase) + const CommonDataPtr & common_data_ptr, const std::vector & objects) { ExtendedPredictedObjects extended_objects; extended_objects.reserve(objects.size()); @@ -1173,7 +1166,7 @@ ExtendedPredictedObjects transform_to_extended_objects( const auto & lc_param = *common_data_ptr->lc_param_ptr; std::transform( objects.begin(), objects.end(), std::back_inserter(extended_objects), [&](const auto & object) { - return utils::lane_change::transform(object, bpp_param, lc_param, check_prepare_phase); + return utils::lane_change::transform(object, bpp_param, lc_param); }); return extended_objects; From 5dcb52b55ea9ef39f330a1a550a91d5db9e1afac Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Mon, 18 Nov 2024 10:23:49 +0900 Subject: [PATCH 023/273] feat(autoware_traffic_light_multi_camera_fusion): resolve clang-tidy error (#9336) * feat(autoware_traffic_light_multi_camera_fusion): resolve clang-tidy error Signed-off-by: Y.Hisaki * add const to argument Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../package.xml | 1 + ...traffic_light_multi_camera_fusion_node.cpp | 6 ++-- ...traffic_light_multi_camera_fusion_node.hpp | 30 +++++++++---------- 3 files changed, 19 insertions(+), 18 deletions(-) diff --git a/perception/autoware_traffic_light_multi_camera_fusion/package.xml b/perception/autoware_traffic_light_multi_camera_fusion/package.xml index e029c79def9f9..111e34030c870 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/package.xml +++ b/perception/autoware_traffic_light_multi_camera_fusion/package.xml @@ -16,6 +16,7 @@ autoware_lanelet2_extension autoware_map_msgs autoware_perception_msgs + message_filters rclcpp rclcpp_components sensor_msgs diff --git a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp index 70841b936af37..08c6600d91923 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp +++ b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp @@ -102,8 +102,8 @@ V at_or(const std::unordered_map & map, const K & key, const V & value) autoware_perception_msgs::msg::TrafficLightElement convert( const tier4_perception_msgs::msg::TrafficLightElement & input) { - typedef tier4_perception_msgs::msg::TrafficLightElement OldElem; - typedef autoware_perception_msgs::msg::TrafficLightElement NewElem; + using OldElem = tier4_perception_msgs::msg::TrafficLightElement; + using NewElem = autoware_perception_msgs::msg::TrafficLightElement; static const std::unordered_map color_map( {{OldElem::RED, NewElem::RED}, {OldElem::AMBER, NewElem::AMBER}, @@ -292,7 +292,7 @@ void MultiCameraFusion::multiCameraFusion(std::map & fused } void MultiCameraFusion::groupFusion( - std::map & fused_record_map, + const std::map & fused_record_map, std::map & grouped_record_map) { grouped_record_map.clear(); diff --git a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.hpp b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.hpp index 23bc59c26b293..bf41df9bb3a24 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.hpp +++ b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.hpp @@ -65,16 +65,16 @@ bool operator<(const FusionRecordArr & r1, const FusionRecordArr & r2) class MultiCameraFusion : public rclcpp::Node { public: - typedef sensor_msgs::msg::CameraInfo CamInfoType; - typedef tier4_perception_msgs::msg::TrafficLightRoi RoiType; - typedef tier4_perception_msgs::msg::TrafficLight SignalType; - typedef tier4_perception_msgs::msg::TrafficLightArray SignalArrayType; - typedef tier4_perception_msgs::msg::TrafficLightRoiArray RoiArrayType; - typedef tier4_perception_msgs::msg::TrafficLightRoi::_traffic_light_id_type IdType; - typedef autoware_perception_msgs::msg::TrafficLightGroup NewSignalType; - typedef autoware_perception_msgs::msg::TrafficLightGroupArray NewSignalArrayType; + using CamInfoType = sensor_msgs::msg::CameraInfo; + using RoiType = tier4_perception_msgs::msg::TrafficLightRoi; + using SignalType = tier4_perception_msgs::msg::TrafficLight; + using SignalArrayType = tier4_perception_msgs::msg::TrafficLightArray; + using RoiArrayType = tier4_perception_msgs::msg::TrafficLightRoiArray; + using IdType = tier4_perception_msgs::msg::TrafficLightRoi::_traffic_light_id_type; + using NewSignalType = autoware_perception_msgs::msg::TrafficLightGroup; + using NewSignalArrayType = autoware_perception_msgs::msg::TrafficLightGroupArray; - typedef std::pair RecordArrayType; + using RecordArrayType = std::pair; explicit MultiCameraFusion(const rclcpp::NodeOptions & node_options); @@ -91,14 +91,14 @@ class MultiCameraFusion : public rclcpp::Node const std::map & grouped_record_map, NewSignalArrayType & msg_out); void groupFusion( - std::map & fused_record_map, + const std::map & fused_record_map, std::map & grouped_record_map); - typedef mf::sync_policies::ExactTime ExactSyncPolicy; - typedef mf::Synchronizer ExactSync; - typedef mf::sync_policies::ApproximateTime - ApproximateSyncPolicy; - typedef mf::Synchronizer ApproximateSync; + using ExactSyncPolicy = mf::sync_policies::ExactTime; + using ExactSync = mf::Synchronizer; + using ApproximateSyncPolicy = + mf::sync_policies::ApproximateTime; + using ApproximateSync = mf::Synchronizer; std::vector>> signal_subs_; std::vector>> roi_subs_; From 93828b6d2570fa88c147da00e78e02bcda473dff Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Nov 2024 10:29:26 +0900 Subject: [PATCH 024/273] feat(bpp): add velocity interface (#9344) * feat(bpp): add velocity interface Signed-off-by: satoshi-ota * fix(adapi): subscribe additional velocity factors Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../src/planner_manager.cpp | 1 + .../interface/scene_module_interface.hpp | 29 ++++++++++++++++++- .../scene_module_manager_interface.hpp | 24 +++++++++++++++ .../scene_module_manager_interface.cpp | 2 ++ .../autoware_default_adapi/src/planning.cpp | 9 +++++- 5 files changed, 63 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp index 29c2d60a30d9f..bd5b391127467 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp @@ -178,6 +178,7 @@ BehaviorModuleOutput PlannerManager::run(const std::shared_ptr & da m->updateObserver(); m->publishRTCStatus(); m->publishSteeringFactor(); + m->publishVelocityFactor(); }); generateCombinedDrivableArea(result_output.valid_output, data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index 60a5faf6cd929..5da5c9ccc6c15 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include #include @@ -57,6 +58,7 @@ namespace autoware::behavior_path_planner { using autoware::motion_utils::SteeringFactorInterface; +using autoware::motion_utils::VelocityFactorInterface; using autoware::objects_of_interest_marker_interface::ColorName; using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface; using autoware::rtc_interface::RTCInterface; @@ -64,6 +66,7 @@ using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::generateUUID; using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::SteeringFactor; +using autoware_adapi_v1_msgs::msg::VelocityFactor; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_planning_msgs::msg::PathWithLaneId; using tier4_planning_msgs::msg::StopFactor; @@ -265,10 +268,16 @@ class SceneModuleInterface StopReason getStopReason() const { return stop_reason_; } - void reset_factor() { steering_factor_interface_.reset(); } + void reset_factor() + { + steering_factor_interface_.reset(); + velocity_factor_interface_.reset(); + } auto get_steering_factor() const -> SteeringFactor { return steering_factor_interface_.get(); } + auto get_velocity_factor() const -> VelocityFactor { return velocity_factor_interface_.get(); } + std::string name() const { return name_; } std::optional getStopPose() const @@ -555,6 +564,22 @@ class SceneModuleInterface } } + void setVelocityFactor(const PathWithLaneId & path) + { + if (stop_pose_.has_value()) { + velocity_factor_interface_.set( + path.points, getEgoPose(), stop_pose_.value(), VelocityFactor::APPROACHING, "stop"); + return; + } + + if (!slow_pose_.has_value()) { + return; + } + + velocity_factor_interface_.set( + path.points, getEgoPose(), slow_pose_.value(), VelocityFactor::APPROACHING, "slow down"); + } + void setStopReason(const std::string & stop_reason, const PathWithLaneId & path) { stop_reason_.reason = stop_reason; @@ -627,6 +652,8 @@ class SceneModuleInterface mutable SteeringFactorInterface steering_factor_interface_; + mutable VelocityFactorInterface velocity_factor_interface_; + mutable std::optional stop_pose_{std::nullopt}; mutable std::optional slow_pose_{std::nullopt}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 65df5e15dad41..e199309dea8bb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -24,6 +24,7 @@ #include #include +#include #include #include @@ -42,6 +43,7 @@ using autoware::motion_utils::createSlowDownVirtualWallMarker; using autoware::motion_utils::createStopVirtualWallMarker; using autoware::universe_utils::toHexString; using autoware_adapi_v1_msgs::msg::SteeringFactorArray; +using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using unique_identifier_msgs::msg::UUID; using SceneModulePtr = std::shared_ptr; using SceneModuleObserver = std::weak_ptr; @@ -124,6 +126,26 @@ class SceneModuleManagerInterface pub_steering_factors_->publish(steering_factor_array); } + void publishVelocityFactor() + { + VelocityFactorArray velocity_factor_array; + velocity_factor_array.header.frame_id = "map"; + velocity_factor_array.header.stamp = node_->now(); + + for (const auto & m : observers_) { + if (m.expired()) { + continue; + } + + const auto velocity_factor = m.lock()->get_velocity_factor(); + if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { + velocity_factor_array.factors.emplace_back(velocity_factor); + } + } + + pub_velocity_factors_->publish(velocity_factor_array); + } + void publishVirtualWall() const { using autoware::universe_utils::appendMarkerArray; @@ -286,6 +308,8 @@ class SceneModuleManagerInterface rclcpp::Publisher::SharedPtr pub_steering_factors_; + rclcpp::Publisher::SharedPtr pub_velocity_factors_; + rclcpp::Publisher::SharedPtr pub_processing_time_; std::string name_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp index 35f29921b97b5..7b362d9a8bafa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp @@ -59,6 +59,8 @@ void SceneModuleManagerInterface::initInterface( "~/processing_time/" + name_, 20); pub_steering_factors_ = node->create_publisher("/planning/steering_factor/" + name_, 1); + pub_velocity_factors_ = + node->create_publisher("/planning/velocity_factors/" + name_, 1); } // misc diff --git a/system/autoware_default_adapi/src/planning.cpp b/system/autoware_default_adapi/src/planning.cpp index 4ff0edfd2b7d5..d89ef6c221666 100644 --- a/system/autoware_default_adapi/src/planning.cpp +++ b/system/autoware_default_adapi/src/planning.cpp @@ -87,7 +87,14 @@ PlanningNode::PlanningNode(const rclcpp::NodeOptions & options) : Node("planning "/planning/velocity_factors/traffic_light", "/planning/velocity_factors/virtual_traffic_light", "/planning/velocity_factors/walkway", - "/planning/velocity_factors/motion_velocity_planner"}; + "/planning/velocity_factors/motion_velocity_planner", + "/planning/velocity_factors/static_obstacle_avoidance", + "/planning/velocity_factors/dynamic_obstacle_avoidance", + "/planning/velocity_factors/avoidance_by_lane_change", + "/planning/velocity_factors/lane_change_left", + "/planning/velocity_factors/lane_change_right", + "/planning/velocity_factors/start_planner", + "/planning/velocity_factors/goal_planner"}; std::vector steering_factor_topics = { "/planning/steering_factor/static_obstacle_avoidance", From c826605107f0bf32d04e95432a355f3c28924579 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Nov 2024 11:09:53 +0900 Subject: [PATCH 025/273] feat(avoidance): output velocity factor (#9345) Signed-off-by: satoshi-ota --- .../src/scene.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index d92e43dcf13bf..01922a16e8a49 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -84,6 +84,7 @@ StaticObstacleAvoidanceModule::StaticObstacleAvoidanceModule( generator_{parameters} { steering_factor_interface_.init(PlanningBehavior::AVOIDANCE); + velocity_factor_interface_.init(PlanningBehavior::AVOIDANCE); } bool StaticObstacleAvoidanceModule::isExecutionRequested() const @@ -769,6 +770,8 @@ void StaticObstacleAvoidanceModule::updateEgoBehavior( insertReturnDeadLine(isBestEffort(parameters_->policy_deceleration), path); setStopReason(StopReason::AVOIDANCE, path.path); + + setVelocityFactor(path.path); } bool StaticObstacleAvoidanceModule::isSafePath( From c5597ce09e5f8fa119dbc268bbbe9d76b2db863a Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Mon, 18 Nov 2024 11:11:00 +0900 Subject: [PATCH 026/273] feat(freespace_planner): add processing time pub (#9332) Signed-off-by: Kasunori-Nakajima --- .../freespace_planner/freespace_planner_node.hpp | 2 ++ .../freespace_planner_node.cpp | 11 +++++++++++ 2 files changed, 13 insertions(+) diff --git a/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp b/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp index 55d7bf966b24f..1f5a52ca040a0 100644 --- a/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp +++ b/planning/autoware_freespace_planner/include/autoware/freespace_planner/freespace_planner_node.hpp @@ -45,6 +45,7 @@ #include #include #include +#include #include #ifdef ROS_DISTRO_GALACTIC @@ -111,6 +112,7 @@ class FreespacePlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr debug_pose_array_pub_; rclcpp::Publisher::SharedPtr debug_partial_pose_array_pub_; rclcpp::Publisher::SharedPtr parking_state_pub_; + rclcpp::Publisher::SharedPtr processing_time_pub_; rclcpp::Subscription::SharedPtr route_sub_; diff --git a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp index a2a4d1f079b3c..f968d668223e0 100644 --- a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include #include @@ -94,6 +95,8 @@ FreespacePlannerNode::FreespacePlannerNode(const rclcpp::NodeOptions & node_opti debug_pose_array_pub_ = create_publisher("~/debug/pose_array", qos); debug_partial_pose_array_pub_ = create_publisher("~/debug/partial_pose_array", qos); parking_state_pub_ = create_publisher("is_completed", qos); + processing_time_pub_ = + create_publisher("~/debug/processing_time_ms", 1); } // TF @@ -277,6 +280,8 @@ bool FreespacePlannerNode::isDataReady() void FreespacePlannerNode::onTimer() { + autoware::universe_utils::StopWatch stop_watch; + scenario_ = scenario_sub_.takeData(); if (!utils::is_active(scenario_)) { reset(); @@ -355,6 +360,12 @@ void FreespacePlannerNode::onTimer() debug_partial_pose_array_pub_->publish(utils::trajectory_to_pose_array(partial_trajectory_)); is_new_parking_cycle_ = false; + + // Publish ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + processing_time_pub_->publish(processing_time_msg); } void FreespacePlannerNode::planTrajectory() From 44d9a9802677629f1801e5ff087a046d878e7479 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Nov 2024 11:28:35 +0900 Subject: [PATCH 027/273] feat(start_planner): output velocity factor (#9347) Signed-off-by: satoshi-ota --- .../src/start_planner_module.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index b303ffb1c71d9..7dd597e27b71f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -98,6 +98,7 @@ StartPlannerModule::StartPlannerModule( } steering_factor_interface_.init(PlanningBehavior::START_PLANNER); + velocity_factor_interface_.init(PlanningBehavior::START_PLANNER); } void StartPlannerModule::onFreespacePlannerTimer() @@ -738,6 +739,8 @@ BehaviorModuleOutput StartPlannerModule::plan() setDrivableAreaInfo(output); + setVelocityFactor(output.path); + const auto steering_factor_direction = getSteeringFactorDirection(output); if (status_.driving_forward) { From 09c01820d9ffe181d32389b505efc31b0242c35a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Nov 2024 11:30:46 +0900 Subject: [PATCH 028/273] feat(lane_change): output velocity factor (#9349) Signed-off-by: satoshi-ota --- .../src/interface.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 4ff2a6cc52e63..44252bb9f2005 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -47,6 +47,7 @@ LaneChangeInterface::LaneChangeInterface( module_type_->setTimeKeeper(getTimeKeeper()); logger_ = utils::lane_change::getLogger(module_type_->getModuleTypeStr()); steering_factor_interface_.init(PlanningBehavior::LANE_CHANGE); + velocity_factor_interface_.init(PlanningBehavior::LANE_CHANGE); } void LaneChangeInterface::processOnExit() @@ -145,6 +146,8 @@ BehaviorModuleOutput LaneChangeInterface::plan() } } + setVelocityFactor(output.path); + return output; } @@ -179,6 +182,8 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() isExecutionReady(), State::WAITING_FOR_EXECUTION); is_abort_path_approved_ = false; + setVelocityFactor(out.path); + return out; } From 4cb6f103f72250f3c72e8cc4d793d419a51fed41 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Nov 2024 11:31:09 +0900 Subject: [PATCH 029/273] feat(goal_planner): output velocity factor (#9348) Signed-off-by: satoshi-ota --- .../src/goal_planner_module.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index f69a0fe2c0a41..4204d8177c5b1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -135,6 +135,7 @@ GoalPlannerModule::GoalPlannerModule( } steering_factor_interface_.init(PlanningBehavior::GOAL_PLANNER); + velocity_factor_interface_.init(PlanningBehavior::GOAL_PLANNER); /** * NOTE: Add `universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);` to functions called @@ -1468,6 +1469,8 @@ void GoalPlannerModule::postProcess() setStopReason(StopReason::GOAL_PLANNER, pull_over_path.full_path()); + setVelocityFactor(pull_over_path.full_path()); + context_data_ = std::nullopt; } From 4a4db996998836399381fe5f30745fbc66e2d7d1 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 18 Nov 2024 15:28:11 +0900 Subject: [PATCH 030/273] feat(mrm_comfortable_stop_operator): add updateParam for mrm comfortable stop (#9353) * add updateParam for mrm comfortable stop Signed-off-by: Daniel Sanchez * remove abs since it is not necessary Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../mrm_comfortable_stop_operator_core.hpp | 7 +++++++ .../mrm_comfortable_stop_operator/package.xml | 1 + .../mrm_comfortable_stop_operator_core.cpp | 20 +++++++++++++++++++ 3 files changed, 28 insertions(+) diff --git a/system/mrm_comfortable_stop_operator/include/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp b/system/mrm_comfortable_stop_operator/include/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp index 7856c23fa3158..eb84191f481f9 100644 --- a/system/mrm_comfortable_stop_operator/include/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp +++ b/system/mrm_comfortable_stop_operator/include/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp @@ -17,6 +17,7 @@ // Core #include +#include // Autoware #include @@ -55,6 +56,9 @@ class MrmComfortableStopOperator : public rclcpp::Node const tier4_system_msgs::srv::OperateMrm::Request::SharedPtr request, const tier4_system_msgs::srv::OperateMrm::Response::SharedPtr response); + rcl_interfaces::msg::SetParametersResult onParameter( + const std::vector & parameters); + // Publisher rclcpp::Publisher::SharedPtr pub_status_; rclcpp::Publisher::SharedPtr pub_velocity_limit_; @@ -72,6 +76,9 @@ class MrmComfortableStopOperator : public rclcpp::Node // States tier4_system_msgs::msg::MrmBehaviorStatus status_; + + // Parameter callback + OnSetParametersCallbackHandle::SharedPtr set_param_res_; }; } // namespace mrm_comfortable_stop_operator diff --git a/system/mrm_comfortable_stop_operator/package.xml b/system/mrm_comfortable_stop_operator/package.xml index 67211c95d4bdf..92a9569bf329a 100644 --- a/system/mrm_comfortable_stop_operator/package.xml +++ b/system/mrm_comfortable_stop_operator/package.xml @@ -12,6 +12,7 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_universe_utils rclcpp rclcpp_components std_msgs diff --git a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp b/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp index 5c9562463f891..6b18555053582 100644 --- a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp +++ b/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp @@ -14,6 +14,8 @@ #include "mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.hpp" +#include + namespace mrm_comfortable_stop_operator { @@ -48,6 +50,10 @@ MrmComfortableStopOperator::MrmComfortableStopOperator(const rclcpp::NodeOptions // Initialize status_.state = tier4_system_msgs::msg::MrmBehaviorStatus::AVAILABLE; + + // Parameter Callback + set_param_res_ = add_on_set_parameters_callback( + std::bind(&MrmComfortableStopOperator::onParameter, this, std::placeholders::_1)); } void MrmComfortableStopOperator::operateComfortableStop( @@ -65,6 +71,20 @@ void MrmComfortableStopOperator::operateComfortableStop( } } +rcl_interfaces::msg::SetParametersResult MrmComfortableStopOperator::onParameter( + const std::vector & parameters) +{ + using autoware::universe_utils::updateParam; + updateParam(parameters, "min_acceleration", params_.min_acceleration); + updateParam(parameters, "max_jerk", params_.max_jerk); + updateParam(parameters, "min_jerk", params_.min_jerk); + + rcl_interfaces::msg::SetParametersResult result; + result.successful = true; + result.reason = "success"; + return result; +} + void MrmComfortableStopOperator::publishStatus() const { auto status = status_; From 2a37cd2c064071522f068b2f535243b465235771 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Mon, 18 Nov 2024 17:40:10 +0900 Subject: [PATCH 031/273] feat(control_evaluator): add processing time publisher (#9339) Signed-off-by: Kasunori-Nakajima --- .../control_evaluator/control_evaluator_node.hpp | 3 +++ .../src/control_evaluator_node.cpp | 9 +++++++++ 2 files changed, 12 insertions(+) diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp index eed263db49bbc..6e4a04964a72c 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp @@ -19,11 +19,13 @@ #include #include +#include #include #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include #include +#include #include #include @@ -77,6 +79,7 @@ class ControlEvaluatorNode : public rclcpp::Node LaneletMapBin, autoware::universe_utils::polling_policy::Newest> vector_map_subscriber_{this, "~/input/vector_map", rclcpp::QoS{1}.transient_local()}; + rclcpp::Publisher::SharedPtr processing_time_pub_; rclcpp::Publisher::SharedPtr metrics_pub_; // update Route Handler diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index 28034eed5f89c..c24dfee571852 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -29,6 +29,8 @@ ControlEvaluatorNode::ControlEvaluatorNode(const rclcpp::NodeOptions & node_opti using std::placeholders::_1; // Publisher + processing_time_pub_ = + this->create_publisher("~/debug/processing_time_ms", 1); metrics_pub_ = create_publisher("~/metrics", 1); // Timer callback to publish evaluator diagnostics @@ -196,6 +198,7 @@ void ControlEvaluatorNode::AddGoalYawDeviationMetricMsg(const Pose & ego_pose) void ControlEvaluatorNode::onTimer() { + autoware::universe_utils::StopWatch stop_watch; const auto traj = traj_sub_.takeData(); const auto odom = odometry_sub_.takeData(); const auto acc = accel_sub_.takeData(); @@ -225,6 +228,12 @@ void ControlEvaluatorNode::onTimer() metrics_msg_.stamp = now(); metrics_pub_->publish(metrics_msg_); metrics_msg_ = MetricArrayMsg{}; + + // Publish processing time + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + processing_time_pub_->publish(processing_time_msg); } } // namespace control_diagnostics From 34fc143383d1447936d005a7d664593bb0d29aad Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Mon, 18 Nov 2024 17:45:31 +0900 Subject: [PATCH 032/273] refactor(autoware_trajectory): refactor autoware_trajectory (#9356) Signed-off-by: Y.Hisaki --- .../trajectory/detail/interpolated_array.hpp | 7 +++- .../detail/interpolator_common_interface.hpp | 41 ++++++++++++++----- .../detail/interpolator_mixin.hpp | 12 ++---- .../detail/nearest_neighbor_common_impl.hpp | 11 ++--- .../detail/stairstep_common_impl.hpp | 10 ++--- .../trajectory/interpolator/interpolator.hpp | 8 ++-- .../trajectory/path_point_with_lane_id.hpp | 10 ++--- .../src/path_point_with_lane_id.cpp | 2 + 8 files changed, 55 insertions(+), 46 deletions(-) diff --git a/common/autoware_trajectory/include/autoware/trajectory/detail/interpolated_array.hpp b/common/autoware_trajectory/include/autoware/trajectory/detail/interpolated_array.hpp index 29c3e9961045a..1ab22d94605dc 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/detail/interpolated_array.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/detail/interpolated_array.hpp @@ -194,13 +194,16 @@ class InterpolatedArray * @param x The position to compute the value at. * @return The interpolated value. */ - T compute(const double & x) const { return interpolator_->compute(x); } + [[nodiscard]] T compute(const double & x) const { return interpolator_->compute(x); } /** * @brief Get the underlying data of the array. * @return A pair containing the axis and values. */ - std::pair, std::vector> get_data() const { return {bases_, values_}; } + [[nodiscard]] std::pair, std::vector> get_data() const + { + return {bases_, values_}; + } }; } // namespace autoware::trajectory::detail diff --git a/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/interpolator_common_interface.hpp b/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/interpolator_common_interface.hpp index 9ce92e9bd02ea..eeca7775a7ff3 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/interpolator_common_interface.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/interpolator_common_interface.hpp @@ -12,10 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -// clang-format off -#ifndef AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ // NOLINT -#define AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ // NOLINT -// clang-format on +#ifndef AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ +#define AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ #include #include @@ -74,17 +72,33 @@ class InterpolatorCommonInterface * Checks that the interpolator has been built and that the input value is within range. * * @param s The input value. - * @throw std::runtime_error if the interpolator has not been built. + * @return The input value, clamped to the range of the interpolator. */ - void validate_compute_input(const double & s) const + [[nodiscard]] double validate_compute_input(const double & s) const { if (s < start() || s > end()) { RCLCPP_WARN( rclcpp::get_logger("Interpolator"), "Input value %f is outside the range of the interpolator [%f, %f].", s, start(), end()); } + return std::clamp(s, start(), end()); } + /** + * @brief Get the index of the interval containing the input value. + * + * This method determines the index of the interval in the bases array that contains the given + * value. It assumes that the bases array is sorted in ascending order. + * + * If `end_inclusive` is true and the input value matches the end of the bases array, + * the method returns the index of the second-to-last interval. + * + * @param s The input value for which to find the interval index. + * @param end_inclusive Whether to include the end value in the last interval. Defaults to true. + * @return The index of the interval containing the input value. + * + * @throw std::out_of_range if the input value is outside the range of the bases array. + */ [[nodiscard]] int32_t get_index(const double & s, bool end_inclusive = true) const { if (end_inclusive && s == end()) { @@ -96,6 +110,13 @@ class InterpolatorCommonInterface } public: + InterpolatorCommonInterface() = default; + virtual ~InterpolatorCommonInterface() = default; + InterpolatorCommonInterface(const InterpolatorCommonInterface & other) = default; + InterpolatorCommonInterface & operator=(const InterpolatorCommonInterface & other) = default; + InterpolatorCommonInterface(InterpolatorCommonInterface && other) noexcept = default; + InterpolatorCommonInterface & operator=(InterpolatorCommonInterface && other) noexcept = default; + /** * @brief Build the interpolator with the given bases and values. * @@ -132,12 +153,10 @@ class InterpolatorCommonInterface */ [[nodiscard]] T compute(const double & s) const { - validate_compute_input(s); - return compute_impl(s); + double clamped_s = validate_compute_input(s); + return compute_impl(clamped_s); } }; } // namespace autoware::trajectory::interpolator::detail -// clang-format off -#endif // AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ // NOLINT -// clang-format on +#endif // AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ diff --git a/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/interpolator_mixin.hpp b/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/interpolator_mixin.hpp index a71bdcf0067cf..c9456ecf8a020 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/interpolator_mixin.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/interpolator_mixin.hpp @@ -12,10 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -// clang-format off -#ifndef AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_MIXIN_HPP_ // NOLINT -#define AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_MIXIN_HPP_ // NOLINT -// clang-format on +#ifndef AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_MIXIN_HPP_ +#define AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_MIXIN_HPP_ #include "autoware/trajectory/interpolator/interpolator.hpp" @@ -40,7 +38,7 @@ namespace autoware::trajectory::interpolator::detail template struct InterpolatorMixin : public InterpolatorInterface { - std::shared_ptr> clone() const override + [[nodiscard]] std::shared_ptr> clone() const override { return std::make_shared(static_cast(*this)); } @@ -85,6 +83,4 @@ struct InterpolatorMixin : public InterpolatorInterface } // namespace autoware::trajectory::interpolator::detail -// clang-format off -#endif // AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_MIXIN_HPP_ // NOLINT -// clang-format on +#endif // AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__INTERPOLATOR_MIXIN_HPP_ diff --git a/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/nearest_neighbor_common_impl.hpp b/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/nearest_neighbor_common_impl.hpp index 94df905ef4815..f02ed5fa8a4c4 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/nearest_neighbor_common_impl.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/interpolator/detail/nearest_neighbor_common_impl.hpp @@ -12,10 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -// clang-format off -#ifndef AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__NEAREST_NEIGHBOR_COMMON_IMPL_HPP_ // NOLINT -#define AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__NEAREST_NEIGHBOR_COMMON_IMPL_HPP_ // NOLINT -// clang-format on +#ifndef AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__NEAREST_NEIGHBOR_COMMON_IMPL_HPP_ +#define AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__NEAREST_NEIGHBOR_COMMON_IMPL_HPP_ #include "autoware/trajectory/interpolator/detail/interpolator_mixin.hpp" @@ -80,6 +78,5 @@ class NearestNeighborCommonImpl : public detail::InterpolatorMixin, T> } // namespace detail } // namespace autoware::trajectory::interpolator -// clang-format off -#endif // AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__STAIRSTEP_COMMON_IMPL_HPP_ // NOLINT -// clang-format on +#endif // AUTOWARE__TRAJECTORY__INTERPOLATOR__DETAIL__STAIRSTEP_COMMON_IMPL_HPP_ diff --git a/common/autoware_trajectory/include/autoware/trajectory/interpolator/interpolator.hpp b/common/autoware_trajectory/include/autoware/trajectory/interpolator/interpolator.hpp index 8503d658a1202..86dbbe8cdbde4 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/interpolator/interpolator.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/interpolator/interpolator.hpp @@ -73,8 +73,8 @@ class InterpolatorInterface : public detail::InterpolatorCommonInterface */ [[nodiscard]] double compute_first_derivative(const double & s) const { - this->validate_compute_input(s); - return compute_first_derivative_impl(s); + double clamped_s = this->validate_compute_input(s); + return compute_first_derivative_impl(clamped_s); } /** @@ -85,8 +85,8 @@ class InterpolatorInterface : public detail::InterpolatorCommonInterface */ [[nodiscard]] double compute_second_derivative(const double & s) const { - this->validate_compute_input(s); - return compute_second_derivative_impl(s); + double clamped_s = this->validate_compute_input(s); + return compute_second_derivative_impl(clamped_s); } [[nodiscard]] virtual std::shared_ptr> clone() const = 0; diff --git a/common/autoware_trajectory/include/autoware/trajectory/path_point_with_lane_id.hpp b/common/autoware_trajectory/include/autoware/trajectory/path_point_with_lane_id.hpp index 4597c0cc61c6e..0ed92a10a7ea4 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/path_point_with_lane_id.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/path_point_with_lane_id.hpp @@ -12,10 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -// clang-format off -#ifndef AUTOWARE__TRAJECTORY__PATH_POINT_WITH_LANE_ID_HPP_ // NOLINT -#define AUTOWARE__TRAJECTORY__PATH_POINT_WITH_LANE_ID_HPP_ // NOLINT -// clang-format on +#ifndef AUTOWARE__TRAJECTORY__PATH_POINT_WITH_LANE_ID_HPP_ +#define AUTOWARE__TRAJECTORY__PATH_POINT_WITH_LANE_ID_HPP_ #include "autoware/trajectory/path_point.hpp" #include "autoware/trajectory/point.hpp" @@ -149,6 +147,4 @@ class Trajectory }; } // namespace autoware::trajectory -// clang-format off -#endif // AUTOWARE__TRAJECTORY__PATH_POINT_WITH_LANE_ID_HPP_ // NOLINT -// clang-format on +#endif // AUTOWARE__TRAJECTORY__PATH_POINT_WITH_LANE_ID_HPP_ diff --git a/common/autoware_trajectory/src/path_point_with_lane_id.cpp b/common/autoware_trajectory/src/path_point_with_lane_id.cpp index 9906c577d45c7..6c983c4dfa0d3 100644 --- a/common/autoware_trajectory/src/path_point_with_lane_id.cpp +++ b/common/autoware_trajectory/src/path_point_with_lane_id.cpp @@ -16,6 +16,8 @@ #include "autoware/trajectory/detail/utils.hpp" +#include + namespace autoware::trajectory { From 9b0ba2d1216e33a04b9d27ef4d3cad526ac58b6a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 18 Nov 2024 17:47:29 +0900 Subject: [PATCH 033/273] fix(factors_panel): sort by distance to stop/decel or point where it starts moving the steering (#9346) Signed-off-by: satoshi-ota --- .../src/velocity_steering_factors_panel.cpp | 22 +++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp index 90ad18fe5af6c..b7ea26e2c6895 100644 --- a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp @@ -104,8 +104,15 @@ void VelocitySteeringFactorsPanel::onVelocityFactors(const VelocityFactorArray:: velocity_factors_table_->clearContents(); velocity_factors_table_->setRowCount(msg->factors.size()); - for (std::size_t i = 0; i < msg->factors.size(); i++) { - const auto & e = msg->factors.at(i); + auto sorted = *msg; + + // sort by distance to the decel/stop point. + std::sort(sorted.factors.begin(), sorted.factors.end(), [](const auto & a, const auto & b) { + return a.distance < b.distance; + }); + + for (std::size_t i = 0; i < sorted.factors.size(); i++) { + const auto & e = sorted.factors.at(i); // behavior { @@ -157,8 +164,15 @@ void VelocitySteeringFactorsPanel::onSteeringFactors(const SteeringFactorArray:: steering_factors_table_->clearContents(); steering_factors_table_->setRowCount(msg->factors.size()); - for (std::size_t i = 0; i < msg->factors.size(); i++) { - const auto & e = msg->factors.at(i); + auto sorted = *msg; + + // sort by distance to the point where it starts moving the steering. + std::sort(sorted.factors.begin(), sorted.factors.end(), [](const auto & a, const auto & b) { + return a.distance.front() < b.distance.front(); + }); + + for (std::size_t i = 0; i < sorted.factors.size(); i++) { + const auto & e = sorted.factors.at(i); // behavior { From 24652f834f73b13b3e4465bfc9ab8335cbe6cdcf Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Mon, 18 Nov 2024 18:05:38 +0900 Subject: [PATCH 034/273] refactor(map_loader)!: prefix package and namespace with autoware (#8927) * make lanelet2_map_visualization independent Signed-off-by: a-maumau * remove unused files Signed-off-by: a-maumau * remove unused package Signed-off-by: a-maumau * fix package name Signed-off-by: a-maumau * add autoware_ prefix Signed-off-by: a-maumau * add autoware to exec name Signed-off-by: a-maumau * add autoware prefix Signed-off-by: a-maumau * removed unnecessary dependency Signed-off-by: a-maumau --------- Signed-off-by: a-maumau --- .github/CODEOWNERS | 1 + .../src/traffic_light_publish_panel.cpp | 2 +- launch/tier4_map_launch/launch/map.launch.xml | 8 ++--- launch/tier4_map_launch/package.xml | 2 +- .../CMakeLists.txt | 18 ++++++++++ .../README.md | 21 +++++++++++ .../launch/lanelet2_map_visualizer.launch.xml | 9 +++++ .../package.xml | 36 +++++++++++++++++++ .../src}/lanelet2_map_visualization_node.cpp | 8 ++--- .../src}/lanelet2_map_visualization_node.hpp | 9 +++-- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 19 +++------- .../README.md | 28 +++------------ .../config/lanelet2_map_loader.param.yaml | 0 .../config/pointcloud_map_loader.param.yaml | 0 .../map_loader/lanelet2_map_loader_node.hpp | 9 +++-- .../launch/lanelet2_map_loader.launch.xml | 15 ++++++++ .../launch/pointcloud_map_loader.launch.xml | 4 +-- .../package.xml | 4 +-- .../schema/lanelet2_map_loader.schema.json | 0 .../schema/pointcloud_map_loader.schema.json | 0 .../script/map_hash_generator | 0 .../lanelet2_local_projector.hpp | 17 +++++---- .../lanelet2_map_loader_node.cpp | 9 +++-- .../differential_map_loader_module.cpp | 3 ++ .../differential_map_loader_module.hpp | 3 ++ .../partial_map_loader_module.cpp | 3 ++ .../partial_map_loader_module.hpp | 3 ++ .../pointcloud_map_loader_module.cpp | 3 ++ .../pointcloud_map_loader_module.hpp | 3 ++ .../pointcloud_map_loader_node.cpp | 5 ++- .../pointcloud_map_loader_node.hpp | 3 ++ .../selected_map_loader_module.cpp | 5 +-- .../selected_map_loader_module.hpp | 3 ++ .../src/pointcloud_map_loader/utils.cpp | 3 ++ .../src/pointcloud_map_loader/utils.hpp | 4 +++ .../test/data/test_map.osm | 0 .../test/lanelet2_map_loader_launch.test.py | 6 ++-- .../test/test_cylinder_box_overlap.cpp | 2 ++ .../test_differential_map_loader_module.cpp | 5 +-- .../test/test_load_pcd_metadata.cpp | 4 +-- .../test/test_partial_map_loader_module.cpp | 5 +-- .../test_pointcloud_map_loader_module.cpp | 3 +- .../test/test_replace_with_absolute_path.cpp | 2 ++ map/autoware_map_projection_loader/README.md | 2 +- .../launch/lanelet2_map_loader.launch.xml | 20 ----------- .../static_centerline_generator.launch.xml | 2 +- .../package.xml | 2 +- .../src/static_centerline_generator_node.cpp | 14 ++++---- .../test_static_centerline_generator.test.py | 2 +- 50 files changed, 215 insertions(+), 114 deletions(-) create mode 100644 map/autoware_lanelet2_map_visualizer/CMakeLists.txt create mode 100644 map/autoware_lanelet2_map_visualizer/README.md create mode 100644 map/autoware_lanelet2_map_visualizer/launch/lanelet2_map_visualizer.launch.xml create mode 100644 map/autoware_lanelet2_map_visualizer/package.xml rename map/{map_loader/src/lanelet2_map_loader => autoware_lanelet2_map_visualizer/src}/lanelet2_map_visualization_node.cpp (98%) rename map/{map_loader/include/map_loader => autoware_lanelet2_map_visualizer/src}/lanelet2_map_visualization_node.hpp (83%) rename map/{map_loader => autoware_map_loader}/CHANGELOG.rst (100%) rename map/{map_loader => autoware_map_loader}/CMakeLists.txt (84%) rename map/{map_loader => autoware_map_loader}/README.md (91%) rename map/{map_loader => autoware_map_loader}/config/lanelet2_map_loader.param.yaml (100%) rename map/{map_loader => autoware_map_loader}/config/pointcloud_map_loader.param.yaml (100%) rename map/{map_loader/include => autoware_map_loader/include/autoware}/map_loader/lanelet2_map_loader_node.hpp (88%) create mode 100644 map/autoware_map_loader/launch/lanelet2_map_loader.launch.xml rename map/{map_loader => autoware_map_loader}/launch/pointcloud_map_loader.launch.xml (73%) rename map/{map_loader => autoware_map_loader}/package.xml (94%) rename map/{map_loader => autoware_map_loader}/schema/lanelet2_map_loader.schema.json (100%) rename map/{map_loader => autoware_map_loader}/schema/pointcloud_map_loader.schema.json (100%) rename map/{map_loader => autoware_map_loader}/script/map_hash_generator (100%) rename map/{map_loader => autoware_map_loader}/src/lanelet2_map_loader/lanelet2_local_projector.hpp (64%) rename map/{map_loader => autoware_map_loader}/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp (96%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/differential_map_loader_module.cpp (98%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/differential_map_loader_module.hpp (96%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/partial_map_loader_module.cpp (97%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/partial_map_loader_module.hpp (96%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp (97%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp (95%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp (97%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp (96%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/selected_map_loader_module.cpp (98%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/selected_map_loader_module.hpp (96%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/utils.cpp (98%) rename map/{map_loader => autoware_map_loader}/src/pointcloud_map_loader/utils.hpp (96%) rename map/{map_loader => autoware_map_loader}/test/data/test_map.osm (100%) rename map/{map_loader => autoware_map_loader}/test/lanelet2_map_loader_launch.test.py (91%) rename map/{map_loader => autoware_map_loader}/test/test_cylinder_box_overlap.cpp (97%) rename map/{map_loader => autoware_map_loader}/test/test_differential_map_loader_module.cpp (94%) rename map/{map_loader => autoware_map_loader}/test/test_load_pcd_metadata.cpp (90%) rename map/{map_loader => autoware_map_loader}/test/test_partial_map_loader_module.cpp (94%) rename map/{map_loader => autoware_map_loader}/test/test_pointcloud_map_loader_module.cpp (96%) rename map/{map_loader => autoware_map_loader}/test/test_replace_with_absolute_path.cpp (95%) delete mode 100644 map/map_loader/launch/lanelet2_map_loader.launch.xml diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 61af2edc5b516..0097a386e47a7 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -97,6 +97,7 @@ localization/yabloc/yabloc_image_processing/** anh.nguyen.2@tier4.jp kento.yabuu 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 localization/yabloc/yabloc_particle_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/yabloc/yabloc_pose_initializer/** 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 +map/autoware_lanelet2_map_visualizer/** 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 map/autoware_map_height_fitter/** 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 map/autoware_map_projection_loader/** 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 map/autoware_map_tf_generator/** 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 diff --git a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp index 2165587493a7a..c4104584f3f3b 100644 --- a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp +++ b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp @@ -364,7 +364,7 @@ void TrafficLightPublishPanel::onTimer() void TrafficLightPublishPanel::onVectorMap(const LaneletMapBin::ConstSharedPtr msg) { if (received_vector_map_) return; - // NOTE: examples from map_loader/lanelet2_map_visualization_node.cpp + // NOTE: examples from autoware_lanelet2_map_visualizer/lanelet2_map_visualization_node.cpp lanelet::LaneletMapPtr lanelet_map(new lanelet::LaneletMap); lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map); lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map); diff --git a/launch/tier4_map_launch/launch/map.launch.xml b/launch/tier4_map_launch/launch/map.launch.xml index 3b30a891ae555..2fbdbc694cacc 100644 --- a/launch/tier4_map_launch/launch/map.launch.xml +++ b/launch/tier4_map_launch/launch/map.launch.xml @@ -20,7 +20,7 @@ - + @@ -31,13 +31,13 @@ - + - + @@ -47,7 +47,7 @@ - + diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index ca2d46db38a52..a5120987605f5 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -18,9 +18,9 @@ ament_cmake_auto autoware_cmake + autoware_map_loader autoware_map_projection_loader autoware_map_tf_generator - map_loader ament_lint_auto autoware_lint_common diff --git a/map/autoware_lanelet2_map_visualizer/CMakeLists.txt b/map/autoware_lanelet2_map_visualizer/CMakeLists.txt new file mode 100644 index 0000000000000..5f2cb4a1f67a1 --- /dev/null +++ b/map/autoware_lanelet2_map_visualizer/CMakeLists.txt @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_lanelet2_map_visualizer) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(lanelet2_map_visualization_node SHARED + src/lanelet2_map_visualization_node.cpp +) + +rclcpp_components_register_node(lanelet2_map_visualization_node + PLUGIN "autoware::lanelet2_map_visualizer::Lanelet2MapVisualizationNode" + EXECUTABLE lanelet2_map_visualization +) + +ament_auto_package(INSTALL_TO_SHARE + launch +) diff --git a/map/autoware_lanelet2_map_visualizer/README.md b/map/autoware_lanelet2_map_visualizer/README.md new file mode 100644 index 0000000000000..b7e86b4a0d62b --- /dev/null +++ b/map/autoware_lanelet2_map_visualizer/README.md @@ -0,0 +1,21 @@ +# autoware_lanelet2_map_visualizer package + +This package provides the features of visualizing the lanelet2 maps. + +## lanelet2_map_visualization + +### Feature + +lanelet2_map_visualization visualizes autoware_map_msgs/LaneletMapBin messages into visualization_msgs/MarkerArray. + +### How to Run + +`ros2 run autoware_lanelet2_map_visualizer lanelet2_map_visualization` + +### Subscribed Topics + +- ~input/lanelet2_map (autoware_map_msgs/LaneletMapBin) : binary data of Lanelet2 Map + +### Published Topics + +- ~output/lanelet2_map_marker (visualization_msgs/MarkerArray) : visualization messages for RViz diff --git a/map/autoware_lanelet2_map_visualizer/launch/lanelet2_map_visualizer.launch.xml b/map/autoware_lanelet2_map_visualizer/launch/lanelet2_map_visualizer.launch.xml new file mode 100644 index 0000000000000..6c6702c6e7904 --- /dev/null +++ b/map/autoware_lanelet2_map_visualizer/launch/lanelet2_map_visualizer.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/map/autoware_lanelet2_map_visualizer/package.xml b/map/autoware_lanelet2_map_visualizer/package.xml new file mode 100644 index 0000000000000..0244a5f010aa4 --- /dev/null +++ b/map/autoware_lanelet2_map_visualizer/package.xml @@ -0,0 +1,36 @@ + + + + autoware_lanelet2_map_visualizer + 0.1.0 + The autoware_lanelet2_map_visualizer package + Yamato Ando + Ryu Yamamoto + Masahiro Sakamoto + Kento Yabuuchi + NGUYEN Viet Anh + Taiki Yamada + Shintaro Sakoda + Mamoru Sobue + + Apache License 2.0 + Ryohsuke Mitsudome + Koji Minoda + + ament_cmake_auto + autoware_cmake + + autoware_lanelet2_extension + autoware_map_msgs + rclcpp + rclcpp_components + tier4_map_msgs + visualization_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp b/map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.cpp similarity index 98% rename from map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp rename to map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.cpp index 4a9aae78e8eb3..ae9e7114cb385 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp +++ b/map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.cpp @@ -31,7 +31,7 @@ * */ -#include "map_loader/lanelet2_map_visualization_node.hpp" +#include "lanelet2_map_visualization_node.hpp" #include #include @@ -49,7 +49,7 @@ #include #include -namespace +namespace autoware::lanelet2_map_visualizer { void insert_marker_array( visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2) @@ -64,7 +64,6 @@ void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, doub cl->b = static_cast(b); cl->a = static_cast(a); } -} // namespace Lanelet2MapVisualizationNode::Lanelet2MapVisualizationNode(const rclcpp::NodeOptions & options) : Node("lanelet2_map_visualization", options) @@ -314,6 +313,7 @@ void Lanelet2MapVisualizationNode::on_map_bin( pub_marker_->publish(map_marker_array); } +} // namespace autoware::lanelet2_map_visualizer #include -RCLCPP_COMPONENTS_REGISTER_NODE(Lanelet2MapVisualizationNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::lanelet2_map_visualizer::Lanelet2MapVisualizationNode) diff --git a/map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp b/map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.hpp similarity index 83% rename from map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp rename to map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.hpp index 049d714ec452a..7694c191f12a2 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp +++ b/map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MAP_LOADER__LANELET2_MAP_VISUALIZATION_NODE_HPP_ -#define MAP_LOADER__LANELET2_MAP_VISUALIZATION_NODE_HPP_ +#ifndef LANELET2_MAP_VISUALIZATION_NODE_HPP_ +#define LANELET2_MAP_VISUALIZATION_NODE_HPP_ #include @@ -23,6 +23,8 @@ #include #include +namespace autoware::lanelet2_map_visualizer +{ class Lanelet2MapVisualizationNode : public rclcpp::Node { public: @@ -36,5 +38,6 @@ class Lanelet2MapVisualizationNode : public rclcpp::Node void on_map_bin(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg); }; +} // namespace autoware::lanelet2_map_visualizer -#endif // MAP_LOADER__LANELET2_MAP_VISUALIZATION_NODE_HPP_ +#endif // LANELET2_MAP_VISUALIZATION_NODE_HPP_ diff --git a/map/map_loader/CHANGELOG.rst b/map/autoware_map_loader/CHANGELOG.rst similarity index 100% rename from map/map_loader/CHANGELOG.rst rename to map/autoware_map_loader/CHANGELOG.rst diff --git a/map/map_loader/CMakeLists.txt b/map/autoware_map_loader/CMakeLists.txt similarity index 84% rename from map/map_loader/CMakeLists.txt rename to map/autoware_map_loader/CMakeLists.txt index 115f7e5b17464..9f8f8681488aa 100644 --- a/map/map_loader/CMakeLists.txt +++ b/map/autoware_map_loader/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(map_loader) +project(autoware_map_loader) find_package(autoware_cmake REQUIRED) autoware_package() @@ -23,8 +23,8 @@ target_include_directories(pointcloud_map_loader_node ) rclcpp_components_register_node(pointcloud_map_loader_node - PLUGIN "PointCloudMapLoaderNode" - EXECUTABLE pointcloud_map_loader + PLUGIN "autoware::map_loader::PointCloudMapLoaderNode" + EXECUTABLE autoware_pointcloud_map_loader ) ament_auto_add_library(lanelet2_map_loader_node SHARED @@ -32,17 +32,8 @@ ament_auto_add_library(lanelet2_map_loader_node SHARED ) rclcpp_components_register_node(lanelet2_map_loader_node - PLUGIN "Lanelet2MapLoaderNode" - EXECUTABLE lanelet2_map_loader -) - -ament_auto_add_library(lanelet2_map_visualization_node SHARED - src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp -) - -rclcpp_components_register_node(lanelet2_map_visualization_node - PLUGIN "Lanelet2MapVisualizationNode" - EXECUTABLE lanelet2_map_visualization + PLUGIN "autoware::map_loader::Lanelet2MapLoaderNode" + EXECUTABLE autoware_lanelet2_map_loader ) if(BUILD_TESTING) diff --git a/map/map_loader/README.md b/map/autoware_map_loader/README.md similarity index 91% rename from map/map_loader/README.md rename to map/autoware_map_loader/README.md index bc3eb80d80339..046c9062081ca 100644 --- a/map/map_loader/README.md +++ b/map/autoware_map_loader/README.md @@ -1,4 +1,4 @@ -# map_loader package +# autoware_map_loader package This package provides the features of loading various maps. @@ -111,7 +111,7 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co ### Parameters -{{ json_to_markdown("map/map_loader/schema/pointcloud_map_loader.schema.json") }} +{{ json_to_markdown("map/autoware_map_loader/schema/pointcloud_map_loader.schema.json") }} ### Interfaces @@ -136,7 +136,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie ### How to run -`ros2 run map_loader lanelet2_map_loader --ros-args -p lanelet2_map_path:=path/to/map.osm` +`ros2 run autoware_map_loader lanelet2_map_loader --ros-args -p lanelet2_map_path:=path/to/map.osm` ### Subscribed Topics @@ -148,27 +148,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie ### Parameters -{{ json_to_markdown("map/map_loader/schema/lanelet2_map_loader.schema.json") }} +{{ json_to_markdown("map/autoware_map_loader/schema/lanelet2_map_loader.schema.json") }} `use_waypoints` decides how to handle a centerline. This flag enables to use the `overwriteLaneletsCenterlineWithWaypoints` function instead of `overwriteLaneletsCenterline`. Please see [the document of the autoware_lanelet2_extension package](https://github.com/autowarefoundation/autoware_lanelet2_extension/blob/main/autoware_lanelet2_extension/docs/lanelet2_format_extension.md#centerline) in detail. - ---- - -## lanelet2_map_visualization - -### Feature - -lanelet2_map_visualization visualizes autoware_map_msgs/LaneletMapBin messages into visualization_msgs/MarkerArray. - -### How to Run - -`ros2 run map_loader lanelet2_map_visualization` - -### Subscribed Topics - -- ~input/lanelet2_map (autoware_map_msgs/LaneletMapBin) : binary data of Lanelet2 Map - -### Published Topics - -- ~output/lanelet2_map_marker (visualization_msgs/MarkerArray) : visualization messages for RViz diff --git a/map/map_loader/config/lanelet2_map_loader.param.yaml b/map/autoware_map_loader/config/lanelet2_map_loader.param.yaml similarity index 100% rename from map/map_loader/config/lanelet2_map_loader.param.yaml rename to map/autoware_map_loader/config/lanelet2_map_loader.param.yaml diff --git a/map/map_loader/config/pointcloud_map_loader.param.yaml b/map/autoware_map_loader/config/pointcloud_map_loader.param.yaml similarity index 100% rename from map/map_loader/config/pointcloud_map_loader.param.yaml rename to map/autoware_map_loader/config/pointcloud_map_loader.param.yaml diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp similarity index 88% rename from map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp rename to map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp index 2d3fbfb2a140f..54d8244ff76e0 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ -#define MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ +#ifndef AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ +#define AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ #include #include @@ -28,6 +28,8 @@ #include #include +namespace autoware::map_loader +{ class Lanelet2MapLoaderNode : public rclcpp::Node { public: @@ -52,5 +54,6 @@ class Lanelet2MapLoaderNode : public rclcpp::Node sub_map_projector_info_; rclcpp::Publisher::SharedPtr pub_map_bin_; }; +} // namespace autoware::map_loader -#endif // MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ +#endif // AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_ diff --git a/map/autoware_map_loader/launch/lanelet2_map_loader.launch.xml b/map/autoware_map_loader/launch/lanelet2_map_loader.launch.xml new file mode 100644 index 0000000000000..48f92550fe404 --- /dev/null +++ b/map/autoware_map_loader/launch/lanelet2_map_loader.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/map/map_loader/launch/pointcloud_map_loader.launch.xml b/map/autoware_map_loader/launch/pointcloud_map_loader.launch.xml similarity index 73% rename from map/map_loader/launch/pointcloud_map_loader.launch.xml rename to map/autoware_map_loader/launch/pointcloud_map_loader.launch.xml index 3633a8fa39a6b..314b3082efff8 100644 --- a/map/map_loader/launch/pointcloud_map_loader.launch.xml +++ b/map/autoware_map_loader/launch/pointcloud_map_loader.launch.xml @@ -1,9 +1,9 @@ - + - + diff --git a/map/map_loader/package.xml b/map/autoware_map_loader/package.xml similarity index 94% rename from map/map_loader/package.xml rename to map/autoware_map_loader/package.xml index 54cfdcb2b07d3..15fc9fd13df64 100644 --- a/map/map_loader/package.xml +++ b/map/autoware_map_loader/package.xml @@ -1,9 +1,9 @@ - map_loader + autoware_map_loader 0.38.0 - The map_loader package + The autoware_map_loader package Yamato Ando Ryu Yamamoto Masahiro Sakamoto diff --git a/map/map_loader/schema/lanelet2_map_loader.schema.json b/map/autoware_map_loader/schema/lanelet2_map_loader.schema.json similarity index 100% rename from map/map_loader/schema/lanelet2_map_loader.schema.json rename to map/autoware_map_loader/schema/lanelet2_map_loader.schema.json diff --git a/map/map_loader/schema/pointcloud_map_loader.schema.json b/map/autoware_map_loader/schema/pointcloud_map_loader.schema.json similarity index 100% rename from map/map_loader/schema/pointcloud_map_loader.schema.json rename to map/autoware_map_loader/schema/pointcloud_map_loader.schema.json diff --git a/map/map_loader/script/map_hash_generator b/map/autoware_map_loader/script/map_hash_generator similarity index 100% rename from map/map_loader/script/map_hash_generator rename to map/autoware_map_loader/script/map_hash_generator diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp similarity index 64% rename from map/map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp rename to map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp index d73ec0d1ee06e..66b0231c01fd4 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp +++ b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp @@ -17,25 +17,24 @@ #include -namespace lanelet::projection +namespace autoware::map_loader { -class LocalProjector : public Projector +class LocalProjector : public lanelet::Projector { public: - LocalProjector() : Projector(Origin(GPSPoint{})) {} + LocalProjector() : Projector(lanelet::Origin(lanelet::GPSPoint{})) {} - BasicPoint3d forward(const GPSPoint & gps) const override // NOLINT + lanelet::BasicPoint3d forward(const lanelet::GPSPoint & gps) const override // NOLINT { - return BasicPoint3d{0.0, 0.0, gps.ele}; + return lanelet::BasicPoint3d{0.0, 0.0, gps.ele}; } - [[nodiscard]] GPSPoint reverse(const BasicPoint3d & point) const override + [[nodiscard]] lanelet::GPSPoint reverse(const lanelet::BasicPoint3d & point) const override { - return GPSPoint{0.0, 0.0, point.z()}; + return lanelet::GPSPoint{0.0, 0.0, point.z()}; } }; - -} // namespace lanelet::projection +} // namespace autoware::map_loader #endif // LANELET2_MAP_LOADER__LANELET2_LOCAL_PROJECTOR_HPP_ diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp similarity index 96% rename from map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp rename to map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index c2334d4589f27..ee1cc4a58a1be 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -31,7 +31,7 @@ * */ -#include "map_loader/lanelet2_map_loader_node.hpp" +#include "autoware/map_loader/lanelet2_map_loader_node.hpp" #include "lanelet2_local_projector.hpp" @@ -52,6 +52,8 @@ #include #include +namespace autoware::map_loader +{ using autoware_map_msgs::msg::LaneletMapBin; using tier4_map_msgs::msg::MapProjectorInfo; @@ -145,7 +147,7 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( return map; } } else { - const lanelet::projection::LocalProjector projector; + const autoware::map_loader::LocalProjector projector; lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); if (!errors.empty()) { @@ -199,6 +201,7 @@ LaneletMapBin Lanelet2MapLoaderNode::create_map_bin_msg( return map_bin_msg; } +} // namespace autoware::map_loader #include -RCLCPP_COMPONENTS_REGISTER_NODE(Lanelet2MapLoaderNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::map_loader::Lanelet2MapLoaderNode) diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp similarity index 98% rename from map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp rename to map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp index da42389dcc69f..160c6f876138d 100644 --- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp @@ -16,6 +16,8 @@ #include +namespace autoware::map_loader +{ DifferentialMapLoaderModule::DifferentialMapLoaderModule( rclcpp::Node * node, std::map pcd_file_metadata_dict) : logger_(node->get_logger()), all_pcd_file_metadata_dict_(std::move(pcd_file_metadata_dict)) @@ -89,3 +91,4 @@ DifferentialMapLoaderModule::load_point_cloud_map_cell_with_id( pointcloud_map_cell_with_id.cell_id = map_id; return pointcloud_map_cell_with_id; } +} // namespace autoware::map_loader diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp similarity index 96% rename from map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp rename to map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp index 690ffeca653c8..5c51e7f6206d6 100644 --- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp @@ -32,6 +32,8 @@ #include #include +namespace autoware::map_loader +{ class DifferentialMapLoaderModule { using GetDifferentialPointCloudMap = autoware_map_msgs::srv::GetDifferentialPointCloudMap; @@ -55,5 +57,6 @@ class DifferentialMapLoaderModule [[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id( const std::string & path, const std::string & map_id) const; }; +} // namespace autoware::map_loader #endif // POINTCLOUD_MAP_LOADER__DIFFERENTIAL_MAP_LOADER_MODULE_HPP_ diff --git a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp similarity index 97% rename from map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp rename to map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp index 62e165dd1005b..afa3da7b82b2d 100644 --- a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp @@ -16,6 +16,8 @@ #include +namespace autoware::map_loader +{ PartialMapLoaderModule::PartialMapLoaderModule( rclcpp::Node * node, std::map pcd_file_metadata_dict) : logger_(node->get_logger()), all_pcd_file_metadata_dict_(std::move(pcd_file_metadata_dict)) @@ -76,3 +78,4 @@ PartialMapLoaderModule::load_point_cloud_map_cell_with_id( pointcloud_map_cell_with_id.cell_id = map_id; return pointcloud_map_cell_with_id; } +} // namespace autoware::map_loader diff --git a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp similarity index 96% rename from map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp rename to map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp index ec97661366419..6660c56ade759 100644 --- a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp @@ -32,6 +32,8 @@ #include #include +namespace autoware::map_loader +{ class PartialMapLoaderModule { using GetPartialPointCloudMap = autoware_map_msgs::srv::GetPartialPointCloudMap; @@ -55,5 +57,6 @@ class PartialMapLoaderModule [[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id( const std::string & path, const std::string & map_id) const; }; +} // namespace autoware::map_loader #endif // POINTCLOUD_MAP_LOADER__PARTIAL_MAP_LOADER_MODULE_HPP_ diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp similarity index 97% rename from map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp rename to map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp index 1754d0b7629a2..0b6521f69ca09 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp @@ -21,6 +21,8 @@ #include #include +namespace autoware::map_loader +{ sensor_msgs::msg::PointCloud2 downsample( const sensor_msgs::msg::PointCloud2 & msg_input, const float leaf_size) { @@ -99,3 +101,4 @@ sensor_msgs::msg::PointCloud2 PointcloudMapLoaderModule::load_pcd_files( return whole_pcd; } +} // namespace autoware::map_loader diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp similarity index 95% rename from map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp rename to map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp index 44f23ded70e37..59145265ecdb4 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp @@ -28,6 +28,8 @@ #include #include +namespace autoware::map_loader +{ class PointcloudMapLoaderModule { public: @@ -42,5 +44,6 @@ class PointcloudMapLoaderModule [[nodiscard]] sensor_msgs::msg::PointCloud2 load_pcd_files( const std::vector & pcd_paths, const boost::optional leaf_size) const; }; +} // namespace autoware::map_loader #endif // POINTCLOUD_MAP_LOADER__POINTCLOUD_MAP_LOADER_MODULE_HPP_ diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp similarity index 97% rename from map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp rename to map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp index c718b25c56694..2500d96650ae3 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp @@ -24,6 +24,8 @@ #include #include +namespace autoware::map_loader +{ namespace fs = std::filesystem; namespace @@ -145,6 +147,7 @@ std::vector PointCloudMapLoaderNode::get_pcd_paths( } return pcd_paths; } +} // namespace autoware::map_loader #include -RCLCPP_COMPONENTS_REGISTER_NODE(PointCloudMapLoaderNode) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::map_loader::PointCloudMapLoaderNode) diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp similarity index 96% rename from map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp rename to map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp index dbc0d584d347b..251575d7d6424 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp @@ -33,6 +33,8 @@ #include #include +namespace autoware::map_loader +{ class PointCloudMapLoaderNode : public rclcpp::Node { public: @@ -50,5 +52,6 @@ class PointCloudMapLoaderNode : public rclcpp::Node std::map get_pcd_metadata( const std::string & pcd_metadata_path, const std::vector & pcd_paths) const; }; +} // namespace autoware::map_loader #endif // POINTCLOUD_MAP_LOADER__POINTCLOUD_MAP_LOADER_NODE_HPP_ diff --git a/map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp similarity index 98% rename from map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp rename to map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp index 76b56341b8632..082d1f545dc14 100644 --- a/map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp @@ -15,7 +15,8 @@ #include "selected_map_loader_module.hpp" #include -namespace + +namespace autoware::map_loader { autoware_map_msgs::msg::PointCloudMapMetaData create_metadata( const std::map & pcd_file_metadata_dict) @@ -42,7 +43,6 @@ autoware_map_msgs::msg::PointCloudMapMetaData create_metadata( return metadata_msg; } -} // namespace SelectedMapLoaderModule::SelectedMapLoaderModule( rclcpp::Node * node, std::map pcd_file_metadata_dict) @@ -107,3 +107,4 @@ SelectedMapLoaderModule::load_point_cloud_map_cell_with_id( pointcloud_map_cell_with_id.cell_id = map_id; return pointcloud_map_cell_with_id; } +} // namespace autoware::map_loader diff --git a/map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp similarity index 96% rename from map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp rename to map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp index eea8b8c1950ae..bc07543d7a6be 100644 --- a/map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp @@ -33,6 +33,8 @@ #include #include +namespace autoware::map_loader +{ class SelectedMapLoaderModule { using GetSelectedPointCloudMap = autoware_map_msgs::srv::GetSelectedPointCloudMap; @@ -55,5 +57,6 @@ class SelectedMapLoaderModule [[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id( const std::string & path, const std::string & map_id) const; }; +} // namespace autoware::map_loader #endif // POINTCLOUD_MAP_LOADER__SELECTED_MAP_LOADER_MODULE_HPP_ diff --git a/map/map_loader/src/pointcloud_map_loader/utils.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp similarity index 98% rename from map/map_loader/src/pointcloud_map_loader/utils.cpp rename to map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp index ea2c2e7033014..172d462947548 100644 --- a/map/map_loader/src/pointcloud_map_loader/utils.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp @@ -20,6 +20,8 @@ #include #include +namespace autoware::map_loader +{ std::map load_pcd_metadata(const std::string & pcd_metadata_path) { YAML::Node config = YAML::LoadFile(pcd_metadata_path); @@ -107,3 +109,4 @@ bool is_grid_within_queried_area( cylinder_and_box_overlap_exists(center_x, center_y, radius, metadata.min, metadata.max); return res; } +} // namespace autoware::map_loader diff --git a/map/map_loader/src/pointcloud_map_loader/utils.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/utils.hpp similarity index 96% rename from map/map_loader/src/pointcloud_map_loader/utils.hpp rename to map/autoware_map_loader/src/pointcloud_map_loader/utils.hpp index 07e8ade5c6f7c..7a3cec7fcc14a 100644 --- a/map/map_loader/src/pointcloud_map_loader/utils.hpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/utils.hpp @@ -26,6 +26,8 @@ #include #include +namespace autoware::map_loader +{ struct PCDFileMetadata { pcl::PointXYZ min; @@ -48,4 +50,6 @@ bool cylinder_and_box_overlap_exists( bool is_grid_within_queried_area( const autoware_map_msgs::msg::AreaInfo area, const PCDFileMetadata metadata); +} // namespace autoware::map_loader + #endif // POINTCLOUD_MAP_LOADER__UTILS_HPP_ diff --git a/map/map_loader/test/data/test_map.osm b/map/autoware_map_loader/test/data/test_map.osm similarity index 100% rename from map/map_loader/test/data/test_map.osm rename to map/autoware_map_loader/test/data/test_map.osm diff --git a/map/map_loader/test/lanelet2_map_loader_launch.test.py b/map/autoware_map_loader/test/lanelet2_map_loader_launch.test.py similarity index 91% rename from map/map_loader/test/lanelet2_map_loader_launch.test.py rename to map/autoware_map_loader/test/lanelet2_map_loader_launch.test.py index 0a29a74e90b06..14f05b1938b61 100644 --- a/map/map_loader/test/lanelet2_map_loader_launch.test.py +++ b/map/autoware_map_loader/test/lanelet2_map_loader_launch.test.py @@ -28,12 +28,12 @@ @pytest.mark.launch_test def generate_test_description(): lanelet2_map_path = os.path.join( - get_package_share_directory("map_loader"), "test/data/test_map.osm" + get_package_share_directory("autoware_map_loader"), "test/data/test_map.osm" ) lanelet2_map_loader = Node( - package="map_loader", - executable="lanelet2_map_loader", + package="autoware_map_loader", + executable="autoware_lanelet2_map_loader", parameters=[ { "lanelet2_map_path": lanelet2_map_path, diff --git a/map/map_loader/test/test_cylinder_box_overlap.cpp b/map/autoware_map_loader/test/test_cylinder_box_overlap.cpp similarity index 97% rename from map/map_loader/test/test_cylinder_box_overlap.cpp rename to map/autoware_map_loader/test/test_cylinder_box_overlap.cpp index d8ca2ca9f8734..6ab0c0a309be0 100644 --- a/map/map_loader/test/test_cylinder_box_overlap.cpp +++ b/map/autoware_map_loader/test/test_cylinder_box_overlap.cpp @@ -16,6 +16,8 @@ #include +using autoware::map_loader::cylinder_and_box_overlap_exists; + TEST(CylinderAndBoxOverlapExists, NoOverlap) { // Cylinder: center = (5, 0), radius = 4 - 0.1 diff --git a/map/map_loader/test/test_differential_map_loader_module.cpp b/map/autoware_map_loader/test/test_differential_map_loader_module.cpp similarity index 94% rename from map/map_loader/test/test_differential_map_loader_module.cpp rename to map/autoware_map_loader/test/test_differential_map_loader_module.cpp index e25a8f97a70ca..cd9b670b32fd3 100644 --- a/map/map_loader/test/test_differential_map_loader_module.cpp +++ b/map/autoware_map_loader/test/test_differential_map_loader_module.cpp @@ -23,6 +23,7 @@ #include +using autoware::map_loader::DifferentialMapLoaderModule; using autoware_map_msgs::srv::GetDifferentialPointCloudMap; class TestDifferentialMapLoaderModule : public ::testing::Test @@ -45,8 +46,8 @@ class TestDifferentialMapLoaderModule : public ::testing::Test pcl::io::savePCDFileASCII("/tmp/dummy.pcd", dummy_cloud); // Generate a sample dummy pointcloud metadata dictionary - std::map dummy_metadata_dict; - PCDFileMetadata dummy_metadata; + std::map dummy_metadata_dict; + autoware::map_loader::PCDFileMetadata dummy_metadata; dummy_metadata.min = pcl::PointXYZ(-1.0, -1.0, -1.0); dummy_metadata.max = pcl::PointXYZ(1.0, 1.0, 1.0); dummy_metadata_dict["/tmp/dummy.pcd"] = dummy_metadata; diff --git a/map/map_loader/test/test_load_pcd_metadata.cpp b/map/autoware_map_loader/test/test_load_pcd_metadata.cpp similarity index 90% rename from map/map_loader/test/test_load_pcd_metadata.cpp rename to map/autoware_map_loader/test/test_load_pcd_metadata.cpp index fcec100f389c5..dc23c3a9fb2d6 100644 --- a/map/map_loader/test/test_load_pcd_metadata.cpp +++ b/map/autoware_map_loader/test/test_load_pcd_metadata.cpp @@ -39,12 +39,12 @@ TEST(LoadPCDMetadataTest, BasicFunctionality) { std::string yaml_file_path = create_yaml_file(); - std::map expected = { + std::map expected = { {"file1.pcd", {{1, 2, 0}, {6, 8, 0}}}, {"file2.pcd", {{3, 4, 0}, {8, 10, 0}}}, }; - auto result = load_pcd_metadata(yaml_file_path); + auto result = autoware::map_loader::load_pcd_metadata(yaml_file_path); ASSERT_THAT(result, ContainerEq(expected)); } diff --git a/map/map_loader/test/test_partial_map_loader_module.cpp b/map/autoware_map_loader/test/test_partial_map_loader_module.cpp similarity index 94% rename from map/map_loader/test/test_partial_map_loader_module.cpp rename to map/autoware_map_loader/test/test_partial_map_loader_module.cpp index 9ff27df29ab8b..fd25b600c81af 100644 --- a/map/map_loader/test/test_partial_map_loader_module.cpp +++ b/map/autoware_map_loader/test/test_partial_map_loader_module.cpp @@ -22,6 +22,7 @@ #include +using autoware::map_loader::PartialMapLoaderModule; using autoware_map_msgs::srv::GetPartialPointCloudMap; class TestPartialMapLoaderModule : public ::testing::Test @@ -44,8 +45,8 @@ class TestPartialMapLoaderModule : public ::testing::Test pcl::io::savePCDFileASCII("/tmp/dummy.pcd", dummy_cloud); // Generate a sample dummy pointcloud metadata dictionary - std::map dummy_metadata_dict; - PCDFileMetadata dummy_metadata; + std::map dummy_metadata_dict; + autoware::map_loader::PCDFileMetadata dummy_metadata; dummy_metadata.min = pcl::PointXYZ(-1.0, -1.0, -1.0); dummy_metadata.max = pcl::PointXYZ(1.0, 1.0, 1.0); dummy_metadata_dict["/tmp/dummy.pcd"] = dummy_metadata; diff --git a/map/map_loader/test/test_pointcloud_map_loader_module.cpp b/map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp similarity index 96% rename from map/map_loader/test/test_pointcloud_map_loader_module.cpp rename to map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp index 5667f476b4dab..d61839d5abfc8 100644 --- a/map/map_loader/test/test_pointcloud_map_loader_module.cpp +++ b/map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp @@ -65,7 +65,8 @@ TEST_F(TestPointcloudMapLoaderModule, LoadPCDFilesNoDownsampleTest) std::vector pcd_paths = {temp_pcd_path}; // Create PointcloudMapLoaderModule instance - PointcloudMapLoaderModule loader(node.get(), pcd_paths, "pointcloud_map_no_downsample", false); + autoware::map_loader::PointcloudMapLoaderModule loader( + node.get(), pcd_paths, "pointcloud_map_no_downsample", false); // Create a subscriber to the published pointcloud topic auto pointcloud_received = std::make_shared(false); diff --git a/map/map_loader/test/test_replace_with_absolute_path.cpp b/map/autoware_map_loader/test/test_replace_with_absolute_path.cpp similarity index 95% rename from map/map_loader/test/test_replace_with_absolute_path.cpp rename to map/autoware_map_loader/test/test_replace_with_absolute_path.cpp index 03d533d41cf18..e8ccfbd5fb9f4 100644 --- a/map/map_loader/test/test_replace_with_absolute_path.cpp +++ b/map/autoware_map_loader/test/test_replace_with_absolute_path.cpp @@ -17,6 +17,8 @@ #include #include +using autoware::map_loader::PCDFileMetadata; +using autoware::map_loader::replace_with_absolute_path; using ::testing::ContainerEq; TEST(ReplaceWithAbsolutePathTest, BasicFunctionality) diff --git a/map/autoware_map_projection_loader/README.md b/map/autoware_map_projection_loader/README.md index 11246c092231e..2568bb2c17df7 100644 --- a/map/autoware_map_projection_loader/README.md +++ b/map/autoware_map_projection_loader/README.md @@ -11,7 +11,7 @@ This is necessary information especially when you want to convert from global (g ## Map projector info file specification -You need to provide a YAML file, namely `map_projector_info.yaml` under the `map_path` directory. For `pointcloud_map_metadata.yaml`, please refer to the Readme of `map_loader`. +You need to provide a YAML file, namely `map_projector_info.yaml` under the `map_path` directory. For `pointcloud_map_metadata.yaml`, please refer to the Readme of `autoware_map_loader`. ```bash sample-map-rosbag diff --git a/map/map_loader/launch/lanelet2_map_loader.launch.xml b/map/map_loader/launch/lanelet2_map_loader.launch.xml deleted file mode 100644 index 5baee911d6572..0000000000000 --- a/map/map_loader/launch/lanelet2_map_loader.launch.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml index 38379a52e4c92..b897cf4d88711 100644 --- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -20,7 +20,7 @@ - + autoware_geography_utils autoware_interpolation autoware_lanelet2_extension + autoware_map_loader autoware_map_msgs autoware_map_projection_loader autoware_mission_planner @@ -33,7 +34,6 @@ autoware_vehicle_info_utils geometry_msgs global_parameter_loader - map_loader rclcpp rclcpp_components tier4_map_msgs diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index a6ba007e71485..398edc215da3e 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -15,6 +15,7 @@ #include "static_centerline_generator_node.hpp" #include "autoware/interpolation/spline_interpolation_points_2d.hpp" +#include "autoware/map_loader/lanelet2_map_loader_node.hpp" #include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp" #include "autoware/map_projection_loader/map_projection_loader.hpp" #include "autoware/motion_utils/resample/resample.hpp" @@ -26,7 +27,6 @@ #include "autoware_lanelet2_extension/utility/utilities.hpp" #include "autoware_static_centerline_generator/msg/points_with_lane_id.hpp" #include "centerline_source/bag_ego_trajectory_based_centerline.hpp" -#include "map_loader/lanelet2_map_loader_node.hpp" #include "type_alias.hpp" #include "utils.hpp" @@ -358,24 +358,24 @@ void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_ // load map map_projector_info_ = std::make_unique( autoware::map_projection_loader::load_info_from_lanelet2_map(lanelet2_input_file_path)); - const auto map_ptr = - Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_); + const auto map_ptr = autoware::map_loader::Lanelet2MapLoaderNode::load_map( + lanelet2_input_file_path, *map_projector_info_); if (!map_ptr) { return nullptr; } // NOTE: The original map is stored here since the centerline will be added to all the // lanelet when lanelet::utils::overwriteLaneletCenterline is called. - original_map_ptr_ = - Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_); + original_map_ptr_ = autoware::map_loader::Lanelet2MapLoaderNode::load_map( + lanelet2_input_file_path, *map_projector_info_); // overwrite more dense centerline // NOTE: overwriteLaneletsCenterlineWithWaypoints is used only in real time calculation. lanelet::utils::overwriteLaneletsCenterline(map_ptr, 5.0, false); // create map bin msg - const auto map_bin_msg = - Lanelet2MapLoaderNode::create_map_bin_msg(map_ptr, lanelet2_input_file_path, now()); + const auto map_bin_msg = autoware::map_loader::Lanelet2MapLoaderNode::create_map_bin_msg( + map_ptr, lanelet2_input_file_path, now()); return std::make_shared(map_bin_msg); }(); diff --git a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py index 4bb0630d13942..ca2621212ef83 100644 --- a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py +++ b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py @@ -71,7 +71,7 @@ def generate_test_description(): "config/path_optimizer.param.yaml", ), os.path.join( - get_package_share_directory("map_loader"), + get_package_share_directory("autoware_map_loader"), "config/lanelet2_map_loader.param.yaml", ), os.path.join( From d813446fba229d393fe157e166531e269dff6c7e Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 18 Nov 2024 20:23:25 +0900 Subject: [PATCH 035/273] perf(static_obstacle_avoidance): remove redundant calculation related to lanelet functions (#9355) * add traffic light distance and modified goal allowance to avoidance data Signed-off-by: Go Sakayori * add closest lanelet related variable to avoidanceData structure Signed-off-by: Go Sakayori * use route handler for checking closest lanelet Signed-off-by: Go Sakayori * use std::optional Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .../data_structs.hpp | 7 ++++ .../helper.hpp | 8 ++-- .../utils.hpp | 11 +++--- .../src/scene.cpp | 28 ++++++++----- .../src/utils.cpp | 39 ++++++++----------- 5 files changed, 53 insertions(+), 40 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 52916275eeb5d..732a364db8e06 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -27,6 +27,7 @@ #include #include +#include #include #include #include @@ -594,6 +595,12 @@ struct AvoidancePlanningData double to_return_point{std::numeric_limits::max()}; + std::optional distance_to_red_traffic_light{std::nullopt}; + + std::optional closest_lanelet{std::nullopt}; + + bool is_allowed_goal_modification{false}; + bool request_operator{false}; }; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp index be6ca8bb9812d..1575d764fffd0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/helper.hpp @@ -212,7 +212,8 @@ class AvoidanceHelper : std::max(shift_length, getRightShiftBound()); } - double getForwardDetectionRange() const + double getForwardDetectionRange( + const std::optional & closest_lanelet) const { if (parameters_->use_static_detection_area) { return parameters_->object_check_max_forward_distance; @@ -220,12 +221,11 @@ class AvoidanceHelper const auto & route_handler = data_->route_handler; - lanelet::ConstLanelet closest_lane; - if (!route_handler->getClosestLaneletWithinRoute(getEgoPose(), &closest_lane)) { + if (!closest_lanelet.has_value()) { return parameters_->object_check_max_forward_distance; } - const auto limit = route_handler->getTrafficRulesPtr()->speedLimit(closest_lane); + const auto limit = route_handler->getTrafficRulesPtr()->speedLimit(closest_lanelet.value()); const auto speed = isShifted() ? limit.speedLimit.value() : getEgoSpeed(); const auto max_shift_length = std::max( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp index 56d1a93ea1799..9509b9954304d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp @@ -54,7 +54,8 @@ double calcShiftLength( const bool & is_object_on_right, const double & overhang_dist, const double & avoid_margin); bool isWithinLanes( - const lanelet::ConstLanelets & lanelets, const std::shared_ptr & planner_data); + const std::optional & closest_lanelet, + const std::shared_ptr & planner_data); /** * @brief check if the ego has to shift driving position. @@ -261,12 +262,12 @@ DrivableLanes generateExpandedDrivableLanes( double calcDistanceToReturnDeadLine( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, const std::shared_ptr & planner_data, - const std::shared_ptr & parameters); + const std::shared_ptr & parameters, + const std::optional distance_to_red_traffic, const bool is_allowed_goal_modification); double calcDistanceToAvoidStartLine( - const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, - const std::shared_ptr & planner_data, - const std::shared_ptr & parameters); + const lanelet::ConstLanelets & lanelets, const std::shared_ptr & parameters, + const std::optional distance_to_red_traffic); /** * @brief calculate error eclipse radius based on object pose covariance. diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 01922a16e8a49..13ef46f9f531f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -32,6 +32,7 @@ #include #include #include +#include #include #include #include @@ -210,9 +211,13 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( data.extend_lanelets = utils::static_obstacle_avoidance::getExtendLanes( data.current_lanelets, getEgoPose(), planner_data_); + lanelet::ConstLanelet closest_lanelet{}; + if (planner_data_->route_handler->getClosestLaneletWithinRoute(getEgoPose(), &closest_lanelet)) + data.closest_lanelet = closest_lanelet; + // expand drivable lanes const auto is_within_current_lane = - utils::static_obstacle_avoidance::isWithinLanes(data.current_lanelets, planner_data_); + utils::static_obstacle_avoidance::isWithinLanes(data.closest_lanelet, planner_data_); const auto red_signal_lane_itr = std::find_if( data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) { if (utils::traffic_light::isTrafficSignalStop({lanelet}, planner_data_)) { @@ -285,11 +290,17 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( data.reference_path, 0, data.reference_path.points.size(), autoware::motion_utils::calcSignedArcLength(data.reference_path.points, getEgoPosition(), 0)); + data.is_allowed_goal_modification = + utils::isAllowedGoalModification(planner_data_->route_handler); + data.distance_to_red_traffic_light = utils::traffic_light::calcDistanceToRedTrafficLight( + data.current_lanelets, data.reference_path_rough, planner_data_); + data.to_return_point = utils::static_obstacle_avoidance::calcDistanceToReturnDeadLine( - data.current_lanelets, data.reference_path_rough, planner_data_, parameters_); + data.current_lanelets, data.reference_path_rough, planner_data_, parameters_, + data.distance_to_red_traffic_light, data.is_allowed_goal_modification); data.to_start_point = utils::static_obstacle_avoidance::calcDistanceToAvoidStartLine( - data.current_lanelets, data.reference_path_rough, planner_data_, parameters_); + data.current_lanelets, parameters_, data.distance_to_red_traffic_light); // filter only for the latest detected objects. fillAvoidanceTargetObjects(data, debug); @@ -323,17 +334,16 @@ void StaticObstacleAvoidanceModule::fillAvoidanceTargetObjects( using utils::static_obstacle_avoidance::filterTargetObjects; using utils::static_obstacle_avoidance::separateObjectsByPath; using utils::static_obstacle_avoidance::updateRoadShoulderDistance; - using utils::traffic_light::calcDistanceToRedTrafficLight; // Separate dynamic objects based on whether they are inside or outside of the expanded lanelets. constexpr double MARGIN = 10.0; const auto forward_detection_range = [&]() { - const auto to_traffic_light = calcDistanceToRedTrafficLight( - data.current_lanelets, helper_->getPreviousReferencePath(), planner_data_); - if (!to_traffic_light.has_value()) { - return helper_->getForwardDetectionRange(); + if (!data.distance_to_red_traffic_light.has_value()) { + return helper_->getForwardDetectionRange(data.closest_lanelet); } - return std::min(helper_->getForwardDetectionRange(), to_traffic_light.value()); + return std::min( + helper_->getForwardDetectionRange(data.closest_lanelet), + data.distance_to_red_traffic_light.value()); }(); const auto [object_within_target_lane, object_outside_target_lane] = separateObjectsByPath( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index 84978286a96c6..cc036b687b105 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include #include @@ -1161,7 +1162,8 @@ double calcShiftLength( } bool isWithinLanes( - const lanelet::ConstLanelets & lanelets, const std::shared_ptr & planner_data) + const std::optional & closest_lanelet, + const std::shared_ptr & planner_data) { const auto & rh = planner_data->route_handler; const auto & ego_pose = planner_data->self_odometry->pose.pose; @@ -1169,8 +1171,7 @@ bool isWithinLanes( const auto footprint = autoware::universe_utils::transformVector( planner_data->parameters.vehicle_info.createFootprint(), transform); - lanelet::ConstLanelet closest_lanelet{}; - if (!lanelet::utils::query::getClosestLanelet(lanelets, ego_pose, &closest_lanelet)) { + if (!closest_lanelet.has_value()) { return true; } @@ -1178,18 +1179,18 @@ bool isWithinLanes( // push previous lanelet lanelet::ConstLanelets prev_lanelet; - if (rh->getPreviousLaneletsWithinRoute(closest_lanelet, &prev_lanelet)) { + if (rh->getPreviousLaneletsWithinRoute(closest_lanelet.value(), &prev_lanelet)) { concat_lanelets.push_back(prev_lanelet.front()); } // push nearest lanelet { - concat_lanelets.push_back(closest_lanelet); + concat_lanelets.push_back(closest_lanelet.value()); } // push next lanelet lanelet::ConstLanelet next_lanelet; - if (rh->getNextLaneletWithinRoute(closest_lanelet, &next_lanelet)) { + if (rh->getNextLaneletWithinRoute(closest_lanelet.value(), &next_lanelet)) { concat_lanelets.push_back(next_lanelet); } @@ -1950,13 +1951,11 @@ void filterTargetObjects( ? autoware::motion_utils::calcSignedArcLength( data.reference_path_rough.points, ego_idx, data.reference_path_rough.points.size() - 1) : std::numeric_limits::max(); - const auto & is_allowed_goal_modification = - utils::isAllowedGoalModification(planner_data->route_handler); for (auto & o : objects) { if (!filtering_utils::isSatisfiedWithCommonCondition( o, data.reference_path_rough, forward_detection_range, to_goal_distance, - planner_data->self_odometry->pose.pose.position, is_allowed_goal_modification, + planner_data->self_odometry->pose.pose.position, data.is_allowed_goal_modification, parameters)) { data.other_objects.push_back(o); continue; @@ -2556,9 +2555,8 @@ DrivableLanes generateExpandedDrivableLanes( } double calcDistanceToAvoidStartLine( - const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, - const std::shared_ptr & planner_data, - const std::shared_ptr & parameters) + const lanelet::ConstLanelets & lanelets, const std::shared_ptr & parameters, + const std::optional distance_to_red_traffic) { if (lanelets.empty()) { return std::numeric_limits::lowest(); @@ -2568,11 +2566,10 @@ double calcDistanceToAvoidStartLine( // dead line stop factor(traffic light) if (parameters->enable_dead_line_for_traffic_light) { - const auto to_traffic_light = calcDistanceToRedTrafficLight(lanelets, path, planner_data); - if (to_traffic_light.has_value()) { + if (distance_to_red_traffic.has_value()) { distance_to_return_dead_line = std::max( distance_to_return_dead_line, - to_traffic_light.value() + parameters->dead_line_buffer_for_traffic_light); + distance_to_red_traffic.value() + parameters->dead_line_buffer_for_traffic_light); } } @@ -2582,7 +2579,8 @@ double calcDistanceToAvoidStartLine( double calcDistanceToReturnDeadLine( const lanelet::ConstLanelets & lanelets, const PathWithLaneId & path, const std::shared_ptr & planner_data, - const std::shared_ptr & parameters) + const std::shared_ptr & parameters, + const std::optional distance_to_red_traffic, const bool is_allowed_goal_modification) { if (lanelets.empty()) { return std::numeric_limits::max(); @@ -2592,18 +2590,15 @@ double calcDistanceToReturnDeadLine( // dead line stop factor(traffic light) if (parameters->enable_dead_line_for_traffic_light) { - const auto to_traffic_light = calcDistanceToRedTrafficLight(lanelets, path, planner_data); - if (to_traffic_light.has_value()) { + if (distance_to_red_traffic.has_value()) { distance_to_return_dead_line = std::min( distance_to_return_dead_line, - to_traffic_light.value() - parameters->dead_line_buffer_for_traffic_light); + distance_to_red_traffic.value() - parameters->dead_line_buffer_for_traffic_light); } } // dead line for goal - if ( - !utils::isAllowedGoalModification(planner_data->route_handler) && - parameters->enable_dead_line_for_goal) { + if (!is_allowed_goal_modification && parameters->enable_dead_line_for_goal) { if (planner_data->route_handler->isInGoalRouteSection(lanelets.back())) { const auto & ego_pos = planner_data->self_odometry->pose.pose.position; const auto to_goal_distance = From 2a2bffa96c8706b490b87dafaab57f4778566acf Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 18 Nov 2024 20:38:52 +0900 Subject: [PATCH 036/273] feat(goal_planner): move goal_candidates from ThreadSafeData to GoalPlannerData (#9292) Signed-off-by: Mamoru Sobue --- .../goal_planner_module.hpp | 8 ++- .../thread_data.hpp | 6 +- .../src/goal_planner_module.cpp | 61 ++++++++++--------- 3 files changed, 40 insertions(+), 35 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index e8c82c0a4600b..2edd0714eceff 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -233,6 +233,8 @@ class GoalPlannerModule : public SceneModuleInterface ModuleStatus current_status; BehaviorModuleOutput previous_module_output; BehaviorModuleOutput last_previous_module_output; // occupancy_grid_map; @@ -244,7 +246,8 @@ class GoalPlannerModule : public SceneModuleInterface void update( const GoalPlannerParameters & parameters, const PlannerData & planner_data, const ModuleStatus & current_status, const BehaviorModuleOutput & previous_module_output, - const autoware::universe_utils::LinearRing2d & vehicle_footprint); + const autoware::universe_utils::LinearRing2d & vehicle_footprint, + const GoalCandidates & goal_candidates); private: void initializeOccupancyGridMap( @@ -309,6 +312,7 @@ class GoalPlannerModule : public SceneModuleInterface // goal searcher std::shared_ptr goal_searcher_; + GoalCandidates goal_candidates_{}; // NOTE: this is latest occupancy_grid_map pointer which the local planner_data on // onFreespaceParkingTimer thread storage may point to while calculation. @@ -409,7 +413,7 @@ class GoalPlannerModule : public SceneModuleInterface // freespace parking bool planFreespacePath( std::shared_ptr planner_data, - const std::shared_ptr goal_searcher, + const std::shared_ptr goal_searcher, const GoalCandidates & goal_candidates, const std::shared_ptr occupancy_grid_map); bool canReturnToLaneParking(const PullOverContextData & context_data); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp index a0d5d40d8c8d5..9df48fb5f0a5f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp @@ -106,7 +106,6 @@ class ThreadSafeData const std::lock_guard lock(mutex_); pull_over_path_ = nullptr; pull_over_path_candidates_.clear(); - goal_candidates_.clear(); last_path_update_time_ = std::nullopt; closest_start_pose_ = std::nullopt; prev_data_ = PathDecisionState{}; @@ -115,6 +114,7 @@ class ThreadSafeData // main --> lane/freespace DEFINE_SETTER_GETTER_WITH_MUTEX(PredictedObjects, static_target_objects) DEFINE_SETTER_GETTER_WITH_MUTEX(PredictedObjects, dynamic_target_objects) + // main --> lane DEFINE_SETTER_GETTER_WITH_MUTEX(PathDecisionState, prev_data) @@ -125,8 +125,6 @@ class ThreadSafeData // main <--> lane/freespace DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_update_time) - - DEFINE_SETTER_GETTER_WITH_MUTEX(GoalCandidates, goal_candidates) DEFINE_SETTER_GETTER_WITH_MUTEX( utils::path_safety_checker::CollisionCheckDebugMap, collision_check) @@ -144,7 +142,6 @@ class ThreadSafeData last_path_update_time_ = clock_->now(); } - void set_no_lock(const GoalCandidates & arg) { goal_candidates_ = arg; } void set_no_lock(const std::vector & arg) { pull_over_path_candidates_ = arg; } void set_no_lock(const std::shared_ptr & arg) { set_pull_over_path_no_lock(arg); } void set_no_lock(const PullOverPath & arg) { set_pull_over_path_no_lock(arg); } @@ -155,7 +152,6 @@ class ThreadSafeData std::shared_ptr pull_over_path_{nullptr}; std::vector pull_over_path_candidates_; - GoalCandidates goal_candidates_{}; std::optional last_path_update_time_; std::optional closest_start_pose_{}; utils::path_safety_checker::CollisionCheckDebugMap collision_check_{}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 4204d8177c5b1..f8a35134e0407 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -210,6 +210,7 @@ void GoalPlannerModule::onTimer() std::optional last_previous_module_output_opt{std::nullopt}; std::shared_ptr occupancy_grid_map{nullptr}; std::optional parameters_opt{std::nullopt}; + std::optional goal_candidates_opt{std::nullopt}; // begin of critical section { @@ -222,12 +223,14 @@ void GoalPlannerModule::onTimer() last_previous_module_output_opt = gp_planner_data.last_previous_module_output; occupancy_grid_map = gp_planner_data.occupancy_grid_map; parameters_opt = gp_planner_data.parameters; + goal_candidates_opt = gp_planner_data.goal_candidates; } } // end of critical section if ( !local_planner_data || !current_status_opt || !previous_module_output_opt || - !last_previous_module_output_opt || !occupancy_grid_map || !parameters_opt) { + !last_previous_module_output_opt || !occupancy_grid_map || !parameters_opt || + !goal_candidates_opt) { RCLCPP_ERROR( getLogger(), "failed to get valid " @@ -239,13 +242,14 @@ void GoalPlannerModule::onTimer() const auto & previous_module_output = previous_module_output_opt.value(); const auto & last_previous_module_output = last_previous_module_output_opt.value(); const auto & parameters = parameters_opt.value(); + const auto & goal_candidates = goal_candidates_opt.value(); if (current_status == ModuleStatus::IDLE) { return; } // goals are not yet available. - if (thread_safe_data_.get_goal_candidates().empty()) { + if (goal_candidates.empty()) { return; } @@ -296,8 +300,6 @@ void GoalPlannerModule::onTimer() return; } - const auto goal_candidates = thread_safe_data_.get_goal_candidates(); - // generate valid pull over path candidates and calculate closest start pose const auto current_lanes = utils::getExtendedCurrentLanes( local_planner_data, parameters.backward_goal_search_length, @@ -376,6 +378,7 @@ void GoalPlannerModule::onFreespaceParkingTimer() std::shared_ptr occupancy_grid_map{nullptr}; std::optional parameters_opt{std::nullopt}; std::optional vehicle_footprint_opt{std::nullopt}; + std::optional goal_candidates_opt{std::nullopt}; // begin of critical section { @@ -387,10 +390,13 @@ void GoalPlannerModule::onFreespaceParkingTimer() occupancy_grid_map = gp_planner_data.occupancy_grid_map; parameters_opt = gp_planner_data.parameters; vehicle_footprint_opt = gp_planner_data.vehicle_footprint; + goal_candidates_opt = gp_planner_data.goal_candidates; } } // end of critical section - if (!local_planner_data || !current_status_opt || !parameters_opt || !vehicle_footprint_opt) { + if ( + !local_planner_data || !current_status_opt || !parameters_opt || !vehicle_footprint_opt || + !goal_candidates_opt) { RCLCPP_ERROR( getLogger(), "failed to get valid planner_data/current_status/parameters in " @@ -401,6 +407,7 @@ void GoalPlannerModule::onFreespaceParkingTimer() const auto & current_status = current_status_opt.value(); const auto & parameters = parameters_opt.value(); const auto & vehicle_footprint = vehicle_footprint_opt.value(); + const auto & goal_candidates = goal_candidates_opt.value(); if (current_status == ModuleStatus::IDLE) { return; @@ -440,7 +447,7 @@ void GoalPlannerModule::onFreespaceParkingTimer() parameters)) { auto goal_searcher = std::make_shared(parameters, vehicle_footprint); - planFreespacePath(local_planner_data, goal_searcher, occupancy_grid_map); + planFreespacePath(local_planner_data, goal_searcher, goal_candidates, occupancy_grid_map); } } @@ -501,6 +508,11 @@ void GoalPlannerModule::updateData() thread_safe_data_.set_static_target_objects(static_target_objects); thread_safe_data_.set_dynamic_target_objects(dynamic_target_objects); + // update goal searcher and generate goal candidates + if (goal_candidates_.empty()) { + goal_candidates_ = generateGoalCandidates(); + } + // In PlannerManager::run(), it calls SceneModuleInterface::setData and // SceneModuleInterface::setPreviousModuleOutput before module_ptr->run(). // Then module_ptr->run() invokes GoalPlannerModule::updateData and then @@ -526,7 +538,7 @@ void GoalPlannerModule::updateData() // and if these two coincided, only the reference count is affected gp_planner_data.update( *parameters_, *planner_data_, getCurrentStatus(), getPreviousModuleOutput(), - vehicle_footprint_); + vehicle_footprint_, goal_candidates_); // NOTE: RouteHandler holds several shared pointers in it, so just copying PlannerData as // value does not adds the reference counts of RouteHandler.lanelet_map_ptr_ and others. Since // behavior_path_planner::run() updates @@ -586,11 +598,6 @@ void GoalPlannerModule::updateData() thread_safe_data_.get_pull_over_path_candidates(), prev_decision_state); auto & ctx_data = context_data_.value(); - // update goal searcher and generate goal candidates - if (thread_safe_data_.get_goal_candidates().empty()) { - thread_safe_data_.set_goal_candidates(generateGoalCandidates()); - } - thread_safe_data_.set_prev_data(path_decision_controller_.get_current_state()); if (!isActivated()) { @@ -760,15 +767,13 @@ double GoalPlannerModule::calcModuleRequestLength() const bool GoalPlannerModule::planFreespacePath( std::shared_ptr planner_data, - const std::shared_ptr goal_searcher, + const std::shared_ptr goal_searcher, const GoalCandidates & goal_candidates_arg, const std::shared_ptr occupancy_grid_map) { - GoalCandidates goal_candidates{}; - goal_candidates = thread_safe_data_.get_goal_candidates(); + auto goal_candidates = goal_candidates_arg; goal_searcher->update( goal_candidates, occupancy_grid_map, planner_data, thread_safe_data_.get_static_target_objects()); - thread_safe_data_.set_goal_candidates(goal_candidates); debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); debug_data_.freespace_planner.is_planning = true; @@ -1370,7 +1375,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( thread_safe_data_.clearPullOverPath(); // update goal candidates - auto goal_candidates = thread_safe_data_.get_goal_candidates(); + auto goal_candidates = goal_candidates_; goal_searcher_->update( goal_candidates, occupancy_grid_map_, planner_data_, context_data.static_target_objects); @@ -1392,7 +1397,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( * As the next action item, only set this selected pull_over_path to only * FreespaceThreadSafeData. */ - thread_safe_data_.set(goal_candidates, pull_over_path); + thread_safe_data_.set(pull_over_path); if (pull_over_path_with_velocity_opt) { auto & pull_over_path_with_velocity = pull_over_path_with_velocity_opt.value(); // copy the path for later setOutput() @@ -1403,8 +1408,6 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( RCLCPP_DEBUG( getLogger(), "selected pull over path: path_id: %ld, goal_id: %ld", pull_over_path.id(), pull_over_path.modified_goal().id); - } else { - thread_safe_data_.set(goal_candidates); } } @@ -1566,8 +1569,8 @@ PathWithLaneId GoalPlannerModule::generateStopPath(const PullOverContextData & c // calculate search start offset pose from the closest goal candidate pose with // approximate_pull_over_distance_ ego vehicle decelerates to this position. or if no feasible // stop point is found, stop at this position. - const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes( - thread_safe_data_.get_goal_candidates(), planner_data_); + const auto closest_goal_candidate = + goal_searcher_->getClosetGoalCandidateAlongLanes(goal_candidates_, planner_data_); const auto decel_pose = calcLongitudinalOffsetPose( extended_prev_path.points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); @@ -1968,8 +1971,8 @@ void GoalPlannerModule::deceleratePath(PullOverPath & pull_over_path) const universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); // decelerate before the search area start - const auto closest_goal_candidate = goal_searcher_->getClosetGoalCandidateAlongLanes( - thread_safe_data_.get_goal_candidates(), planner_data_); + const auto closest_goal_candidate = + goal_searcher_->getClosetGoalCandidateAlongLanes(goal_candidates_, planner_data_); const auto decel_pose = calcLongitudinalOffsetPose( pull_over_path.full_path().points, closest_goal_candidate.goal_pose.position, -approximate_pull_over_distance_); @@ -2371,8 +2374,7 @@ void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) goal_searcher_->getAreaPolygons(), header, color, z)); // Visualize goal candidates - const auto goal_candidates = thread_safe_data_.get_goal_candidates(); - add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates, color)); + add(goal_planner_utils::createGoalCandidatesMarkerArray(goal_candidates_, color)); // Visualize objects extraction polygon auto marker = autoware::universe_utils::createDefaultMarker( @@ -2595,14 +2597,16 @@ GoalPlannerModule::GoalPlannerData GoalPlannerModule::GoalPlannerData::clone() c GoalPlannerModule::GoalPlannerData gp_planner_data( planner_data, parameters, last_previous_module_output); gp_planner_data.update( - parameters, planner_data, current_status, previous_module_output, vehicle_footprint); + parameters, planner_data, current_status, previous_module_output, vehicle_footprint, + goal_candidates); return gp_planner_data; } void GoalPlannerModule::GoalPlannerData::update( const GoalPlannerParameters & parameters_, const PlannerData & planner_data_, const ModuleStatus & current_status_, const BehaviorModuleOutput & previous_module_output_, - const autoware::universe_utils::LinearRing2d & vehicle_footprint_) + const autoware::universe_utils::LinearRing2d & vehicle_footprint_, + const GoalCandidates & goal_candidates_) { parameters = parameters_; vehicle_footprint = vehicle_footprint_; @@ -2613,6 +2617,7 @@ void GoalPlannerModule::GoalPlannerData::update( last_previous_module_output = previous_module_output; previous_module_output = previous_module_output_; occupancy_grid_map->setMap(*(planner_data.occupancy_grid)); + goal_candidates = goal_candidates_; } void PathDecisionStateController::transit_state( From f112f652bb85b7b980f3b1d7a7bb2c133cc84c61 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Mon, 18 Nov 2024 14:43:53 +0100 Subject: [PATCH 037/273] refactor(traffic_light_utils): prefix package and namespace with autoware (#9251) Signed-off-by: Esteve Fernandez --- .github/CODEOWNERS | 2 +- common/.pages | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 6 +++--- .../README.md | 2 +- .../traffic_light_utils/traffic_light_utils.hpp | 10 +++++----- .../package.xml | 4 ++-- .../src/traffic_light_utils.cpp | 6 +++--- .../test/test_traffic_light_utils.cpp | 6 +++--- .../package.xml | 2 +- .../src/node.cpp | 5 +++-- .../src/node.hpp | 2 +- .../autoware_behavior_path_planner_common/package.xml | 2 +- .../src/utils/traffic_light_utils.cpp | 6 +++--- .../package.xml | 2 +- .../src/scene.cpp | 4 ++-- .../package.xml | 2 +- .../src/filter_predicted_objects.cpp | 2 +- .../src/out_of_lane_module.cpp | 5 +++-- 19 files changed, 36 insertions(+), 34 deletions(-) rename common/{traffic_light_utils => autoware_traffic_light_utils}/CHANGELOG.rst (100%) rename common/{traffic_light_utils => autoware_traffic_light_utils}/CMakeLists.txt (76%) rename common/{traffic_light_utils => autoware_traffic_light_utils}/README.md (90%) rename common/{traffic_light_utils/include => autoware_traffic_light_utils/include/autoware}/traffic_light_utils/traffic_light_utils.hpp (92%) rename common/{traffic_light_utils => autoware_traffic_light_utils}/package.xml (88%) rename common/{traffic_light_utils => autoware_traffic_light_utils}/src/traffic_light_utils.cpp (95%) rename common/{traffic_light_utils => autoware_traffic_light_utils}/test/test_traffic_light_utils.cpp (93%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 0097a386e47a7..df6be468e726f 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -25,6 +25,7 @@ common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp ta common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_trajectory/** mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yukinari.hisaki.2@tier4.jp +common/autoware_traffic_light_utils/** kotaro.uetake@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp @@ -41,7 +42,6 @@ common/tier4_system_rviz_plugin/** koji.minoda@tier4.jp common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp -common/traffic_light_utils/** kotaro.uetake@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp control/autoware_autonomous_emergency_braking/** daniel.sanchez@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/autoware_collision_detector/** go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp tomohito.ando@tier4.jp control/autoware_control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp diff --git a/common/.pages b/common/.pages index cd0423fa8de79..2ca956927b905 100644 --- a/common/.pages +++ b/common/.pages @@ -22,8 +22,8 @@ nav: - 'Signal Processing': - 'Introduction': common/autoware_signal_processing - 'Butterworth Filter': common/autoware_signal_processing/documentation/ButterworthFilter + - 'autoware_traffic_light_utils': common/autoware_traffic_light_utils - 'autoware_universe_utils': common/autoware_universe_utils - - 'traffic_light_utils': common/traffic_light_utils - 'RVIZ2 Plugins': - 'autoware_perception_rviz_plugin': common/autoware_perception_rviz_plugin - 'autoware_overlay_rviz_plugin': common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin diff --git a/common/traffic_light_utils/CHANGELOG.rst b/common/autoware_traffic_light_utils/CHANGELOG.rst similarity index 100% rename from common/traffic_light_utils/CHANGELOG.rst rename to common/autoware_traffic_light_utils/CHANGELOG.rst diff --git a/common/traffic_light_utils/CMakeLists.txt b/common/autoware_traffic_light_utils/CMakeLists.txt similarity index 76% rename from common/traffic_light_utils/CMakeLists.txt rename to common/autoware_traffic_light_utils/CMakeLists.txt index 741bdd585ed7f..2c9d11994290e 100644 --- a/common/traffic_light_utils/CMakeLists.txt +++ b/common/autoware_traffic_light_utils/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(traffic_light_utils) +project(autoware_traffic_light_utils) find_package(autoware_cmake REQUIRED) autoware_package() @@ -7,7 +7,7 @@ autoware_package() find_package(Boost REQUIRED) find_package(autoware_cmake REQUIRED) -ament_auto_add_library(traffic_light_utils SHARED +ament_auto_add_library(${PROJECT_NAME} SHARED src/traffic_light_utils.cpp ) @@ -16,7 +16,7 @@ if(BUILD_TESTING) file(GLOB_RECURSE TEST_SOURCES test/*.cpp) ament_add_ros_isolated_gtest(test_traffic_light_utils ${TEST_SOURCES}) target_include_directories(test_traffic_light_utils PRIVATE src/include) - target_link_libraries(test_traffic_light_utils traffic_light_utils) + target_link_libraries(test_traffic_light_utils ${PROJECT_NAME}) endif() ament_auto_package() diff --git a/common/traffic_light_utils/README.md b/common/autoware_traffic_light_utils/README.md similarity index 90% rename from common/traffic_light_utils/README.md rename to common/autoware_traffic_light_utils/README.md index 0963a33bc1c4e..d13fddd35f987 100644 --- a/common/traffic_light_utils/README.md +++ b/common/autoware_traffic_light_utils/README.md @@ -1,4 +1,4 @@ -# traffic_light_utils +# autoware_traffic_light_utils ## Purpose diff --git a/common/traffic_light_utils/include/traffic_light_utils/traffic_light_utils.hpp b/common/autoware_traffic_light_utils/include/autoware/traffic_light_utils/traffic_light_utils.hpp similarity index 92% rename from common/traffic_light_utils/include/traffic_light_utils/traffic_light_utils.hpp rename to common/autoware_traffic_light_utils/include/autoware/traffic_light_utils/traffic_light_utils.hpp index 3a40c0c3b1d51..bb2500c5d9f63 100644 --- a/common/traffic_light_utils/include/traffic_light_utils/traffic_light_utils.hpp +++ b/common/autoware_traffic_light_utils/include/autoware/traffic_light_utils/traffic_light_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef TRAFFIC_LIGHT_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ -#define TRAFFIC_LIGHT_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ +#ifndef AUTOWARE__TRAFFIC_LIGHT_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ +#define AUTOWARE__TRAFFIC_LIGHT_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ #include "autoware_perception_msgs/msg/traffic_light_element.hpp" #include "autoware_perception_msgs/msg/traffic_light_group.hpp" @@ -27,7 +27,7 @@ #include #include -namespace traffic_light_utils +namespace autoware::traffic_light_utils { void setSignalUnknown(tier4_perception_msgs::msg::TrafficLight & signal, float confidence = -1); @@ -79,6 +79,6 @@ tf2::Vector3 getTrafficLightBottomRight(const lanelet::ConstLineString3d & traff tf2::Vector3 getTrafficLightCenter(const lanelet::ConstLineString3d & traffic_light); -} // namespace traffic_light_utils +} // namespace autoware::traffic_light_utils -#endif // TRAFFIC_LIGHT_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ +#endif // AUTOWARE__TRAFFIC_LIGHT_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ diff --git a/common/traffic_light_utils/package.xml b/common/autoware_traffic_light_utils/package.xml similarity index 88% rename from common/traffic_light_utils/package.xml rename to common/autoware_traffic_light_utils/package.xml index 82955eb4c82c4..384839d1c91d4 100644 --- a/common/traffic_light_utils/package.xml +++ b/common/autoware_traffic_light_utils/package.xml @@ -1,9 +1,9 @@ - traffic_light_utils + autoware_traffic_light_utils 0.38.0 - The traffic_light_utils package + The autoware_traffic_light_utils package Kotaro Uetake Shunsuke Miura Satoshi Ota diff --git a/common/traffic_light_utils/src/traffic_light_utils.cpp b/common/autoware_traffic_light_utils/src/traffic_light_utils.cpp similarity index 95% rename from common/traffic_light_utils/src/traffic_light_utils.cpp rename to common/autoware_traffic_light_utils/src/traffic_light_utils.cpp index a3da21c1bb578..4ba7e1c1d57d8 100644 --- a/common/traffic_light_utils/src/traffic_light_utils.cpp +++ b/common/autoware_traffic_light_utils/src/traffic_light_utils.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "traffic_light_utils/traffic_light_utils.hpp" +#include "autoware/traffic_light_utils/traffic_light_utils.hpp" -namespace traffic_light_utils +namespace autoware::traffic_light_utils { void setSignalUnknown(tier4_perception_msgs::msg::TrafficLight & signal, float confidence) @@ -105,4 +105,4 @@ tf2::Vector3 getTrafficLightCenter(const lanelet::ConstLineString3d & traffic_li return (top_left + bottom_right) / 2; } -} // namespace traffic_light_utils +} // namespace autoware::traffic_light_utils diff --git a/common/traffic_light_utils/test/test_traffic_light_utils.cpp b/common/autoware_traffic_light_utils/test/test_traffic_light_utils.cpp similarity index 93% rename from common/traffic_light_utils/test/test_traffic_light_utils.cpp rename to common/autoware_traffic_light_utils/test/test_traffic_light_utils.cpp index a9e601370945d..856e8b5e9828b 100644 --- a/common/traffic_light_utils/test/test_traffic_light_utils.cpp +++ b/common/autoware_traffic_light_utils/test/test_traffic_light_utils.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware/traffic_light_utils/traffic_light_utils.hpp" #include "gtest/gtest.h" -#include "traffic_light_utils/traffic_light_utils.hpp" -namespace traffic_light_utils +namespace autoware::traffic_light_utils { TEST(setSignalUnknown, set_signal_element) @@ -53,4 +53,4 @@ TEST(getTrafficLightCenter, get_signal) EXPECT_FLOAT_EQ(getTrafficLightCenter(test_light).z(), (float)1.5); } -} // namespace traffic_light_utils +} // namespace autoware::traffic_light_utils diff --git a/perception/autoware_traffic_light_occlusion_predictor/package.xml b/perception/autoware_traffic_light_occlusion_predictor/package.xml index 8817ec2c97647..bebe2ae189e74 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/package.xml +++ b/perception/autoware_traffic_light_occlusion_predictor/package.xml @@ -15,6 +15,7 @@ autoware_lanelet2_extension autoware_map_msgs + autoware_traffic_light_utils autoware_universe_utils geometry_msgs image_geometry @@ -27,7 +28,6 @@ tf2_eigen tf2_ros tier4_perception_msgs - traffic_light_utils ament_lint_auto autoware_lint_common diff --git a/perception/autoware_traffic_light_occlusion_predictor/src/node.cpp b/perception/autoware_traffic_light_occlusion_predictor/src/node.cpp index 8bc11fdea2aad..16498eb4d7094 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/src/node.cpp +++ b/perception/autoware_traffic_light_occlusion_predictor/src/node.cpp @@ -117,7 +117,8 @@ void TrafficLightOcclusionPredictorNode::mapCallback( continue; } lanelet::ConstLineString3d string3d = static_cast(lsp); - traffic_light_position_map_[lsp.id()] = traffic_light_utils::getTrafficLightCenter(string3d); + traffic_light_position_map_[lsp.id()] = + autoware::traffic_light_utils::getTrafficLightCenter(string3d); } } } @@ -166,7 +167,7 @@ void TrafficLightOcclusionPredictorNode::syncCallback( out_msg_.signals.push_back(in_signal_msg->signals.at(i)); if (occlusion_ratios[i] >= config_.max_occlusion_ratio) { - traffic_light_utils::setSignalUnknown(out_msg_.signals.at(predicted_num + i), 0.0); + autoware::traffic_light_utils::setSignalUnknown(out_msg_.signals.at(predicted_num + i), 0.0); } } diff --git a/perception/autoware_traffic_light_occlusion_predictor/src/node.hpp b/perception/autoware_traffic_light_occlusion_predictor/src/node.hpp index 5ee4876a6abbf..bc3afcac8db13 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/src/node.hpp +++ b/perception/autoware_traffic_light_occlusion_predictor/src/node.hpp @@ -17,9 +17,9 @@ #include "occlusion_predictor.hpp" +#include #include #include -#include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml index dea42c692b880..5b925bd5ffd8e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml @@ -54,6 +54,7 @@ autoware_planning_msgs autoware_route_handler autoware_rtc_interface + autoware_traffic_light_utils autoware_universe_utils autoware_vehicle_info_utils geometry_msgs @@ -61,7 +62,6 @@ rclcpp tf2 tier4_planning_msgs - traffic_light_utils visualization_msgs ament_cmake_ros diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp index 14332d953819e..19c9bbcf365a3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp @@ -14,7 +14,7 @@ #include #include -#include +#include namespace autoware::behavior_path_planner::utils::traffic_light { @@ -91,7 +91,7 @@ std::optional calcDistanceToRedTrafficLight( continue; } - if (!traffic_light_utils::isTrafficSignalStop( + if (!autoware::traffic_light_utils::isTrafficSignalStop( lanelet, traffic_signal_stamped.value().signal)) { continue; } @@ -143,7 +143,7 @@ bool isTrafficSignalStop( continue; } - if (traffic_light_utils::isTrafficSignalStop( + if (autoware::traffic_light_utils::isTrafficSignalStop( lanelet, traffic_signal_stamped.value().signal)) { return true; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml index 9cff5fb92b54b..244d03553351b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml @@ -25,6 +25,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_route_handler + autoware_traffic_light_utils autoware_universe_utils eigen geometry_msgs @@ -34,7 +35,6 @@ tf2_eigen tf2_geometry_msgs tier4_planning_msgs - traffic_light_utils visualization_msgs ament_cmake_ros diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index 4b17f95358be6..c59071f2043bb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include #include @@ -177,7 +177,7 @@ bool TrafficLightModule::isStopSignal() } // Check if the current traffic signal state requires stopping - return traffic_light_utils::isTrafficSignalStop(lane_, looking_tl_state_); + return autoware::traffic_light_utils::isTrafficSignalStop(lane_, looking_tl_state_); } void TrafficLightModule::updateTrafficSignal() diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml index 6c8122e816555..18e072191905e 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml @@ -21,6 +21,7 @@ autoware_perception_msgs autoware_planning_msgs autoware_route_handler + autoware_traffic_light_utils autoware_universe_utils autoware_vehicle_info_utils geometry_msgs @@ -29,7 +30,6 @@ rclcpp tf2 tier4_planning_msgs - traffic_light_utils visualization_msgs ament_cmake_ros diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp index 652e941e905e4..f9ba7f4af9877 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp @@ -15,8 +15,8 @@ #include "filter_predicted_objects.hpp" #include +#include #include -#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp index 03a8468d19b3a..63ca1b5784fe8 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/out_of_lane_module.cpp @@ -26,11 +26,11 @@ #include #include #include +#include #include #include #include #include -#include #include #include @@ -179,7 +179,8 @@ void prepare_stop_lines_rtree( const auto traffic_signal_stamped = planner_data.get_traffic_signal(element->id()); if ( traffic_signal_stamped.has_value() && element->stopLine().has_value() && - traffic_light_utils::isTrafficSignalStop(ll, traffic_signal_stamped.value().signal)) { + autoware::traffic_light_utils::isTrafficSignalStop( + ll, traffic_signal_stamped.value().signal)) { stop_line_node.second.stop_line.clear(); for (const auto & p : element->stopLine()->basicLineString()) { stop_line_node.second.stop_line.emplace_back(p.x(), p.y()); From 9aab36bb0faba049d9a2d5e3cc0ecae9f4393ce2 Mon Sep 17 00:00:00 2001 From: Yutaka Kondo Date: Tue, 19 Nov 2024 11:23:01 +0900 Subject: [PATCH 038/273] chore(perception_utils): install include directory (#9354) --- perception/perception_utils/CMakeLists.txt | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/perception/perception_utils/CMakeLists.txt b/perception/perception_utils/CMakeLists.txt index e4b581928cc5e..5623d830918fe 100644 --- a/perception/perception_utils/CMakeLists.txt +++ b/perception/perception_utils/CMakeLists.txt @@ -13,6 +13,11 @@ target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS} ) +install( + DIRECTORY include/ + DESTINATION include +) + if(BUILD_TESTING) ament_auto_add_gtest(test_utils test/test_utils.cpp From ef36c36d160a1c2a15d5064e058c4e267718f1c3 Mon Sep 17 00:00:00 2001 From: "Kem (TiankuiXian)" <1041084556@qq.com> Date: Tue, 19 Nov 2024 11:44:20 +0900 Subject: [PATCH 039/273] feat(tier4_control_launch): use preset.yaml to control which modules to launch for control modules (#9351) * update contro.launch for preset.xml Signed-off-by: xtk8532704 <1041084556@qq.com> * update options. Signed-off-by: xtk8532704 <1041084556@qq.com> * fix bug. Signed-off-by: xtk8532704 <1041084556@qq.com> * rename to enable_* Signed-off-by: xtk8532704 <1041084556@qq.com> * check group. Signed-off-by: xtk8532704 <1041084556@qq.com> * space. Signed-off-by: xtk8532704 <1041084556@qq.com> * reduce num of load_composable_node. Signed-off-by: xtk8532704 <1041084556@qq.com> * tmp save. Signed-off-by: xtk8532704 <1041084556@qq.com> * tmp save. Signed-off-by: xtk8532704 <1041084556@qq.com> * splite control modules' launch. Signed-off-by: xtk8532704 <1041084556@qq.com> * final version Signed-off-by: xtk8532704 <1041084556@qq.com> * remove on/off option for shift decider, vehicle cmd gate, and operation mode transition manager Signed-off-by: xtk8532704 <1041084556@qq.com> * pre-commit Signed-off-by: xtk8532704 <1041084556@qq.com> --------- Signed-off-by: xtk8532704 <1041084556@qq.com> --- .../launch/control.launch.xml | 313 ++++++++++-------- 1 file changed, 169 insertions(+), 144 deletions(-) diff --git a/launch/tier4_control_launch/launch/control.launch.xml b/launch/tier4_control_launch/launch/control.launch.xml index acb81df58c641..899db1448dbf8 100644 --- a/launch/tier4_control_launch/launch/control.launch.xml +++ b/launch/tier4_control_launch/launch/control.launch.xml @@ -1,13 +1,23 @@ - - + + - - - - + + + + + + + + + + + + + + @@ -39,47 +49,9 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + @@ -89,7 +61,6 @@ - @@ -130,7 +101,6 @@ - + - - - + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - + + + + - - - - - - + + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + + - - + + + + + + + + + + + + + + + - - - - - - - - - + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + From 802f906c8d8a666d5b9621dbf58b473aa7c2e7ba Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Tue, 19 Nov 2024 12:39:46 +0900 Subject: [PATCH 040/273] perf(static_obstacle_avoidance): use lanelet::utils instead of route handle for closest lanelet (#9367) use lanelet::utils for performance improvement Signed-off-by: Go Sakayori --- .../src/scene.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 13ef46f9f531f..f0fc87648bc4a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -212,7 +212,8 @@ void StaticObstacleAvoidanceModule::fillFundamentalData( data.current_lanelets, getEgoPose(), planner_data_); lanelet::ConstLanelet closest_lanelet{}; - if (planner_data_->route_handler->getClosestLaneletWithinRoute(getEgoPose(), &closest_lanelet)) + if (lanelet::utils::query::getClosestLanelet( + data.current_lanelets, getEgoPose(), &closest_lanelet)) data.closest_lanelet = closest_lanelet; // expand drivable lanes From 2ce051049d08e9254a59033f552e41b66a308af9 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 19 Nov 2024 13:28:04 +0900 Subject: [PATCH 041/273] fix(compare_map_segmentation): timer period mismatched with parameter (#9259) Signed-off-by: badai-nguyen --- .../src/voxel_grid_map_loader/voxel_grid_map_loader.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) 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 6e927db4e298b..b57874d7d3b24 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 @@ -311,7 +311,8 @@ VoxelGridDynamicMapLoader::VoxelGridDynamicMapLoader( RCLCPP_INFO(logger_, "service not available, waiting again ..."); } - const auto period_ns = rclcpp::Rate(timer_interval_ms).period(); + const auto period_ns = std::chrono::duration_cast( + std::chrono::milliseconds(timer_interval_ms)); timer_callback_group_ = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); map_update_timer_ = rclcpp::create_timer( node, node->get_clock(), period_ns, std::bind(&VoxelGridDynamicMapLoader::timer_callback, this), From dbb1015991d8fb2c4c575f608515e957d23a282a Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 19 Nov 2024 13:28:23 +0900 Subject: [PATCH 042/273] chore(compare_map_segmentation): add maintainer (#9371) Signed-off-by: badai-nguyen --- perception/autoware_compare_map_segmentation/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/perception/autoware_compare_map_segmentation/package.xml b/perception/autoware_compare_map_segmentation/package.xml index b7d497b704bb7..de3d97df91c6f 100644 --- a/perception/autoware_compare_map_segmentation/package.xml +++ b/perception/autoware_compare_map_segmentation/package.xml @@ -7,6 +7,7 @@ amc-nu Yukihiro Saito Dai Nguyen + Yoshi Ri Apache License 2.0 From bcd7830a28404b55f0bf58a6c12c37c7fbd47d80 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 19 Nov 2024 14:06:14 +0900 Subject: [PATCH 043/273] feat(autoware_multi_object_tracker): new function to add odometry uncertainty (#9139) * feat: add Odometry uncertainty to object tracking Signed-off-by: Taekjin LEE * feat: Add odometry heading uncertainty to object pose covariance feat: Rotate object pose covariance matrix to account for yaw uncertainty Rotate the object pose covariance matrix in the uncertainty_processor.cpp file to account for the yaw uncertainty. This ensures that the covariance matrix accurately represents the position uncertainty of the object. Refactor the code to rotate the covariance matrix using Eigen's Rotation2D class. The yaw uncertainty is added to the y-y element of the rotated covariance matrix. Finally, update the object_pose_cov array with the updated covariance values. Closes #123 Signed-off-by: Taekjin LEE * feat: Add odometry motion uncertainty to object pose covariance Signed-off-by: Taekjin LEE refactoring Signed-off-by: Taekjin LEE * feat: Update ego twist uncertainty to the object velocity uncertainty Signed-off-by: Taekjin LEE * feat: update object twist covariance by odometry yaw rate uncertainty Signed-off-by: Taekjin LEE * feat: move uncertainty modeling to input side Signed-off-by: Taekjin LEE * feat: add option to select odometry uncertainty Signed-off-by: Taekjin LEE * refactor: rename consider_odometry_uncertainty to enable_odometry_uncertainty Signed-off-by: Taekjin LEE * fix: transform to world first, add odometry covariance later Signed-off-by: Taekjin LEE style(pre-commit): autofix Signed-off-by: Taekjin LEE * feat: Add odometry heading uncertainty to object pose covariance Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../multi_object_tracker_node.param.yaml | 1 + .../uncertainty/uncertainty_processor.hpp | 3 + .../lib/uncertainty/uncertainty_processor.cpp | 101 ++++++++++++++++++ .../autoware_multi_object_tracker/package.xml | 1 + .../src/multi_object_tracker_node.cpp | 45 ++++++-- .../src/multi_object_tracker_node.hpp | 1 + .../src/processor/input_manager.cpp | 11 +- 7 files changed, 154 insertions(+), 9 deletions(-) diff --git a/perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml b/perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml index 09621a40c499f..7dd588ec8eeba 100644 --- a/perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml +++ b/perception/autoware_multi_object_tracker/config/multi_object_tracker_node.param.yaml @@ -13,6 +13,7 @@ publish_rate: 10.0 world_frame_id: map enable_delay_compensation: false + consider_odometry_uncertainty: false # debug parameters publish_processing_time: false diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp index c67e71b38a6f9..12bd865795b85 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp @@ -23,6 +23,7 @@ #include #include +#include namespace autoware::multi_object_tracker { @@ -34,6 +35,7 @@ using autoware::multi_object_tracker::object_model::ObjectModel; using autoware_perception_msgs::msg::DetectedObject; using autoware_perception_msgs::msg::DetectedObjects; using autoware_perception_msgs::msg::ObjectClassification; +using nav_msgs::msg::Odometry; ObjectModel decodeObjectModel(const ObjectClassification & object_class); @@ -44,6 +46,7 @@ object_model::StateCovariance covarianceFromObjectClass( void normalizeUncertainty(DetectedObjects & detected_objects); +void addOdometryUncertainty(const Odometry & odometry, DetectedObjects & detected_objects); } // namespace uncertainty } // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp index 840879f9bd7aa..3f0b854931842 100644 --- a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp +++ b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp @@ -17,6 +17,9 @@ #include "autoware/multi_object_tracker/uncertainty/uncertainty_processor.hpp" +#include +#include + namespace autoware::multi_object_tracker { namespace uncertainty @@ -135,5 +138,103 @@ void normalizeUncertainty(DetectedObjects & detected_objects) } } +void addOdometryUncertainty(const Odometry & odometry, DetectedObjects & detected_objects) +{ + const auto & odom_pose = odometry.pose.pose; + const auto & odom_pose_cov = odometry.pose.covariance; + const auto & odom_twist = odometry.twist.twist; + const auto & odom_twist_cov = odometry.twist.covariance; + + // ego motion uncertainty, velocity multiplied by time uncertainty + const double ego_yaw = tf2::getYaw(odom_pose.orientation); + const double dt = + (rclcpp::Time(odometry.header.stamp) - rclcpp::Time(detected_objects.header.stamp)).seconds(); + const double dt2 = dt * dt; + Eigen::MatrixXd m_rot_ego = Eigen::Rotation2D(ego_yaw).toRotationMatrix(); + Eigen::MatrixXd m_cov_motion = Eigen::MatrixXd(2, 2); + m_cov_motion << odom_twist.linear.x * odom_twist.linear.x * dt2, 0, 0, + odom_twist.linear.y * odom_twist.linear.y * dt2; + + // ego position uncertainty, position covariance + motion covariance + Eigen::MatrixXd m_cov_ego_pose = Eigen::MatrixXd(2, 2); + m_cov_ego_pose << odom_pose_cov[0], odom_pose_cov[1], odom_pose_cov[6], odom_pose_cov[7]; + m_cov_ego_pose = m_cov_ego_pose + m_rot_ego * m_cov_motion * m_rot_ego.transpose(); + + // ego yaw uncertainty, position covariance + yaw motion covariance + const double & cov_ego_yaw = odom_pose_cov[35]; + const double cov_yaw = cov_ego_yaw + odom_twist.angular.z * odom_twist.angular.z * dt2; + + // ego velocity uncertainty, velocity covariance + Eigen::MatrixXd m_cov_ego_twist = Eigen::MatrixXd(2, 2); + m_cov_ego_twist << odom_twist_cov[0], odom_twist_cov[1], odom_twist_cov[6], odom_twist_cov[7]; + const double & cov_yaw_rate = odom_twist_cov[35]; + + for (auto & object : detected_objects.objects) { + auto & object_pose = object.kinematics.pose_with_covariance.pose; + auto & object_pose_cov = object.kinematics.pose_with_covariance.covariance; + const double dx = object_pose.position.x - odom_pose.position.x; + const double dy = object_pose.position.y - odom_pose.position.y; + const double r2 = dx * dx + dy * dy; + const double theta = std::atan2(dy, dx); + + // 1. add odometry position and motion uncertainty to the object position covariance + Eigen::MatrixXd m_pose_cov = Eigen::MatrixXd(2, 2); + m_pose_cov << object_pose_cov[XYZRPY_COV_IDX::X_X], object_pose_cov[XYZRPY_COV_IDX::X_Y], + object_pose_cov[XYZRPY_COV_IDX::Y_X], object_pose_cov[XYZRPY_COV_IDX::Y_Y]; + + // 1-a. add odometry position uncertainty to the object position covariance + // object position and it covariance is based on the world frame (map) + m_pose_cov = m_pose_cov + m_cov_ego_pose; + + // 1-b. add odometry heading uncertainty to the object position covariance + // uncertainty is proportional to the distance and the uncertainty orientation is vertical to + // the vector to the object + { + const double cov_by_yaw = cov_ego_yaw * r2; + // rotate the covariance matrix, add the yaw uncertainty, and rotate back + Eigen::MatrixXd m_rot_theta = Eigen::Rotation2D(theta).toRotationMatrix(); + Eigen::MatrixXd m_cov_rot = m_rot_theta.transpose() * m_pose_cov * m_rot_theta; + m_cov_rot(1, 1) += cov_by_yaw; // yaw uncertainty is added to y-y element + m_pose_cov = m_rot_theta * m_cov_rot * m_rot_theta.transpose(); + } + // 1-c. add odometry yaw uncertainty to the object yaw covariance + object_pose_cov[XYZRPY_COV_IDX::YAW_YAW] += cov_yaw; // yaw-yaw + + // update the covariance matrix + object_pose_cov[XYZRPY_COV_IDX::X_X] = m_pose_cov(0, 0); + object_pose_cov[XYZRPY_COV_IDX::X_Y] = m_pose_cov(0, 1); + object_pose_cov[XYZRPY_COV_IDX::Y_X] = m_pose_cov(1, 0); + object_pose_cov[XYZRPY_COV_IDX::Y_Y] = m_pose_cov(1, 1); + + // 2. add odometry velocity uncertainty to the object velocity covariance + auto & object_twist_cov = object.kinematics.twist_with_covariance.covariance; + Eigen::MatrixXd m_twist_cov = Eigen::MatrixXd(2, 2); + m_twist_cov << object_twist_cov[XYZRPY_COV_IDX::X_X], object_twist_cov[XYZRPY_COV_IDX::X_Y], + object_twist_cov[XYZRPY_COV_IDX::Y_X], object_twist_cov[XYZRPY_COV_IDX::Y_Y]; + + // 2-a. add odometry velocity uncertainty to the object linear twist covariance + { + const double obj_yaw = tf2::getYaw(object_pose.orientation); // object yaw is global frame + Eigen::MatrixXd m_rot_theta = Eigen::Rotation2D(obj_yaw - ego_yaw).toRotationMatrix(); + m_twist_cov = m_twist_cov + m_rot_theta.transpose() * m_cov_ego_twist * m_rot_theta; + } + + // 2-b. add odometry yaw rate uncertainty to the object linear twist covariance + { + const double cov_by_yaw_rate = cov_yaw_rate * r2; + Eigen::MatrixXd m_rot_theta = Eigen::Rotation2D(theta).toRotationMatrix(); + Eigen::MatrixXd m_twist_cov_rot = m_rot_theta.transpose() * m_twist_cov * m_rot_theta; + m_twist_cov_rot(1, 1) += cov_by_yaw_rate; // yaw rate uncertainty is added to y-y element + m_twist_cov = m_rot_theta * m_twist_cov_rot * m_rot_theta.transpose(); + } + + // update the covariance matrix + object_twist_cov[XYZRPY_COV_IDX::X_X] = m_twist_cov(0, 0); + object_twist_cov[XYZRPY_COV_IDX::X_Y] = m_twist_cov(0, 1); + object_twist_cov[XYZRPY_COV_IDX::Y_X] = m_twist_cov(1, 0); + object_twist_cov[XYZRPY_COV_IDX::Y_Y] = m_twist_cov(1, 1); + } +} + } // namespace uncertainty } // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/package.xml b/perception/autoware_multi_object_tracker/package.xml index e16e4c0d2a836..5eb591d60133f 100644 --- a/perception/autoware_multi_object_tracker/package.xml +++ b/perception/autoware_multi_object_tracker/package.xml @@ -21,6 +21,7 @@ eigen glog mussp + nav_msgs rclcpp rclcpp_components tf2 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 24bf4ef9c123d..68a356cd91da5 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 @@ -87,6 +87,7 @@ MultiObjectTracker::MultiObjectTracker(const rclcpp::NodeOptions & node_options) double publish_rate = declare_parameter("publish_rate"); // [hz] world_frame_id_ = declare_parameter("world_frame_id"); bool enable_delay_compensation{declare_parameter("enable_delay_compensation")}; + enable_odometry_uncertainty_ = declare_parameter("consider_odometry_uncertainty"); declare_parameter("selected_input_channels", std::vector()); std::vector selected_input_channels = @@ -274,19 +275,49 @@ void MultiObjectTracker::runProcess( return; } - // Model the object uncertainty if it is empty - DetectedObjects input_objects_with_uncertainty = uncertainty::modelUncertainty(input_objects); - - // Normalize the object uncertainty - uncertainty::normalizeUncertainty(input_objects_with_uncertainty); - // Transform the objects to the world frame DetectedObjects transformed_objects; if (!autoware::object_recognition_utils::transformObjects( - input_objects_with_uncertainty, world_frame_id_, tf_buffer_, transformed_objects)) { + input_objects, world_frame_id_, tf_buffer_, transformed_objects)) { return; } + // the object uncertainty + if (enable_odometry_uncertainty_) { + // Create a modeled odometry message + nav_msgs::msg::Odometry odometry; + odometry.header.stamp = measurement_time + rclcpp::Duration::from_seconds(0.001); + + // set odometry pose from self_transform + auto & odom_pose = odometry.pose.pose; + odom_pose.position.x = self_transform->translation.x; + odom_pose.position.y = self_transform->translation.y; + odom_pose.position.z = self_transform->translation.z; + odom_pose.orientation = self_transform->rotation; + + // set odometry twist + auto & odom_twist = odometry.twist.twist; + odom_twist.linear.x = 10.0; // m/s + odom_twist.linear.y = 0.1; // m/s + odom_twist.angular.z = 0.1; // rad/s + + // model the uncertainty + auto & odom_pose_cov = odometry.pose.covariance; + odom_pose_cov[0] = 0.1; // x-x + odom_pose_cov[7] = 0.1; // y-y + odom_pose_cov[35] = 0.0001; // yaw-yaw + + auto & odom_twist_cov = odometry.twist.covariance; + odom_twist_cov[0] = 2.0; // x-x [m^2/s^2] + odom_twist_cov[7] = 0.2; // y-y [m^2/s^2] + odom_twist_cov[35] = 0.001; // yaw-yaw [rad^2/s^2] + + // Add the odometry uncertainty to the object uncertainty + uncertainty::addOdometryUncertainty(odometry, transformed_objects); + } + // Normalize the object uncertainty + uncertainty::normalizeUncertainty(transformed_objects); + /* prediction */ processor_->predict(measurement_time); 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 04d83ebd47acb..b9886ee3fc847 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 @@ -87,6 +87,7 @@ class MultiObjectTracker : public rclcpp::Node std::string world_frame_id_; // tracking frame std::unique_ptr association_; std::unique_ptr processor_; + bool enable_odometry_uncertainty_; // input manager std::unique_ptr input_manager_; diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp index decd2139c5b81..c9ee8dae9562a 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp @@ -14,6 +14,8 @@ #include "input_manager.hpp" +#include + #include namespace autoware::multi_object_tracker @@ -49,8 +51,13 @@ void InputStream::init(const InputChannel & input_channel) void InputStream::onMessage( const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr msg) { - const DetectedObjects objects = *msg; - objects_que_.push_back(objects); + const DetectedObjects & objects = *msg; + + // Model the object uncertainty only if it is not available + DetectedObjects objects_with_uncertainty = uncertainty::modelUncertainty(objects); + + // Move the objects_with_uncertainty to the objects queue + objects_que_.push_back(std::move(objects_with_uncertainty)); while (objects_que_.size() > que_size_) { objects_que_.pop_front(); } From 5fcd19626c6af7d3f4782e15879a33fc03786219 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 19 Nov 2024 14:24:33 +0900 Subject: [PATCH 044/273] fix(autoware_behavior_path_sampling_planner_module): fix invalid parameter file (#9231) Signed-off-by: mitsudome-r Co-authored-by: Yutaka Kondo --- .../config/sampling_planner.param.yaml | 39 ++++++++++++++++++- 1 file changed, 38 insertions(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/config/sampling_planner.param.yaml b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/config/sampling_planner.param.yaml index f485ac3ac08b6..9a6b30c219d63 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/config/sampling_planner.param.yaml +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/config/sampling_planner.param.yaml @@ -1,3 +1,40 @@ /**: ros__parameters: - start_planner: + common: + output_delta_arc_length: 0.5 # [m] delta arc length for output trajectory + + debug: + enable_calculation_time_info: false # flag to print calculation times + id: 0 # id of the candidate paths for which to print/show details (e.g., footprint in rviz) + + preprocessing: + force_zero_initial_deviation: True # if true, initial planning starts from the reference path + force_zero_initial_heading: True # if true, initial planning starts with a heading aligned with the reference path + smooth_reference_trajectory: False # if true, the reference trajectory is smoothed before being used for planning + constraints: + hard: + max_curvature: 3.0 # [m⁻¹] maximum curvature of a sampled path + min_curvature: -3.0 # [m⁻¹] minimum curvature of a sampled path + soft: + lateral_deviation_weight: 1.0 # cost weight for lateral deviation between the end of a sampled path and the reference path + length_weight: 1.0 # cost weight for the length of a sampled path + curvature_weight: 2000.0 # cost weight for the curvature of a sampled path + weights: [0.5,1.0,20.0] + sampling: + enable_frenet: True + enable_bezier: False + resolution: 0.5 # [m] target distance between sampled path points + previous_path_reuse_points_nb: 2 # number of points reused from the previously generated path (0:no reuse, 1:replan from end of prev path, 2: end and mid of prev path, etc) + target_lengths: [20.0, 40.0] # [m] target lengths of the sampled paths + nb_target_lateral_positions: 0 # number of lateral positions to use for sampling (in addition to 0.0 and the current lateral deviation) + target_lateral_positions: [-4.5,-2.5, 0.0, 2.5,4.5] # manual values that are only used if nb_target_lateral_positions = 0 + frenet: # target values for the sampled "lateral deviation over longitudinal position" polynomial + target_lateral_velocities: [-0.5, 0.0, 0.5] + target_lateral_accelerations: [0.0] + # bezier: + # nb_k: 3 # number of sampled curvature values + # mk_min: 0.0 # minimum curvature value + # mk_max: 10.0 # maximum curvature value + # nb_t: 5 # number of sampled acceleration values + # mt_min: 0.3 # minimum acceleration value + # mt_max: 1.7 # maximum acceleration value From d1eb8be4675b895ae3e3943bf4836d674d80d347 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Tue, 19 Nov 2024 14:25:28 +0900 Subject: [PATCH 045/273] chore(autoware_mpc_lateral_controller): add maintainer (#9374) Signed-off-by: Kyoichi Sugahara --- control/autoware_mpc_lateral_controller/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml index ec7be46fb9f00..a965343ad3e98 100644 --- a/control/autoware_mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -7,6 +7,7 @@ Takamasa Horibe Takayuki Murooka + Kyoichi Sugahara Apache 2.0 From 245802e53f94ae2272ddbcfe5418ae2140098667 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 19 Nov 2024 14:37:42 +0900 Subject: [PATCH 046/273] fix(yabloc_pose_initializer): include opencv as system (#9375) Signed-off-by: veqcc --- localization/yabloc/yabloc_pose_initializer/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt b/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt index 2e6d31ae2f12b..d67c0e73eb91f 100644 --- a/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt +++ b/localization/yabloc/yabloc_pose_initializer/CMakeLists.txt @@ -27,7 +27,7 @@ ament_auto_add_library(${PROJECT_NAME} src/camera/semantic_segmentation.cpp src/camera/camera_pose_initializer_core.cpp) target_include_directories(${PROJECT_NAME} PUBLIC include) -target_include_directories(${PROJECT_NAME} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS}) +target_include_directories(${PROJECT_NAME} SYSTEM PRIVATE ${EIGEN3_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS} ${OpenCV_INCLUDE_DIRS}) target_link_libraries(${PROJECT_NAME} ${PCL_LIBRARIES} Sophus::Sophus) ament_target_dependencies(${PROJECT_NAME} OpenCV) From 8e0648474774cc05c2ac52eff5003bb66bfc5a48 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 19 Nov 2024 14:48:12 +0900 Subject: [PATCH 047/273] fix(autoware_pose_estimator_arbiter): add missing include (#9376) Signed-off-by: veqcc --- localization/autoware_pose_estimator_arbiter/src/shared_data.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/localization/autoware_pose_estimator_arbiter/src/shared_data.hpp b/localization/autoware_pose_estimator_arbiter/src/shared_data.hpp index 6332b77a9ed31..884daa7ee7580 100644 --- a/localization/autoware_pose_estimator_arbiter/src/shared_data.hpp +++ b/localization/autoware_pose_estimator_arbiter/src/shared_data.hpp @@ -21,6 +21,7 @@ #include #include +#include #include #include #include From a1c3e6dc65f8eefaddb37a905501ce32b6e16fc9 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 19 Nov 2024 15:15:46 +0900 Subject: [PATCH 048/273] fix(autoware_trajectory_follower_node): fix clang-diagnostic-format-security (#9378) Signed-off-by: veqcc --- .../autoware_trajectory_follower_node/src/controller_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/control/autoware_trajectory_follower_node/src/controller_node.cpp b/control/autoware_trajectory_follower_node/src/controller_node.cpp index 7dfbefadca52c..f4a32444afe9d 100644 --- a/control/autoware_trajectory_follower_node/src/controller_node.cpp +++ b/control/autoware_trajectory_follower_node/src/controller_node.cpp @@ -142,8 +142,8 @@ bool Controller::processData(rclcpp::Clock & clock) bool is_ready = true; const auto & logData = [&clock, this](const std::string & data_type) { - std::string msg = "Waiting for " + data_type + " data"; - RCLCPP_INFO_THROTTLE(get_logger(), clock, logger_throttle_interval, msg.c_str()); + RCLCPP_INFO_THROTTLE( + get_logger(), clock, logger_throttle_interval, "Waiting for %s data", data_type.c_str()); }; const auto & getData = [&logData](auto & dest, auto & sub, const std::string & data_type = "") { From 332a9bb600b2bb42ee00e0b78a4a5a3010dc3aa7 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 19 Nov 2024 16:00:54 +0900 Subject: [PATCH 049/273] fix(autoware_control_validator): fix clang-diagnostic-unused-private-field (#9381) Signed-off-by: veqcc --- .../include/autoware/control_validator/control_validator.hpp | 1 - 1 file changed, 1 deletion(-) 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 86ffac1ec371e..080e8f0e6abc3 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 @@ -149,7 +149,6 @@ class ControlValidator : public rclcpp::Node ControlValidatorStatus validation_status_; ValidationParams validation_params_; // for thresholds - bool is_velocity_valid_{true}; autoware::signal_processing::LowpassFilter1d vehicle_vel_{0.0}; autoware::signal_processing::LowpassFilter1d target_vel_{0.0}; bool hold_velocity_error_until_stop_{false}; From 5778e0188c6887a40c844508088770dfdf6c6c92 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 19 Nov 2024 17:33:35 +0900 Subject: [PATCH 050/273] fix(control_performance_analysis): clang-diagnostic-pessimizing-move (#9380) Signed-off-by: veqcc --- .../src/control_performance_analysis_core.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/control/control_performance_analysis/src/control_performance_analysis_core.cpp b/control/control_performance_analysis/src/control_performance_analysis_core.cpp index 5f72c8ea316bd..769593ac34d09 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_core.cpp +++ b/control/control_performance_analysis/src/control_performance_analysis_core.cpp @@ -335,8 +335,7 @@ bool ControlPerformanceAnalysisCore::calculateDrivingVars() lpf(curr.desired_steering_angle.data, prev->desired_steering_angle.data); } - prev_driving_vars_ = - std::move(std::make_unique(driving_status_vars)); + prev_driving_vars_ = std::make_unique(driving_status_vars); last_odom_header.stamp = odom_history_ptr_->at(odom_size - 1).header.stamp; last_steering_report.stamp = current_vec_steering_msg_ptr_->stamp; From 2e0d5de5195ef515d292505c64cdf7893d971c2d Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Tue, 19 Nov 2024 21:12:19 +0900 Subject: [PATCH 051/273] test(bpp_common): add unit test for safety check (#9386) * fix docstring Signed-off-by: Go Sakayori * add basic collision test Signed-off-by: Go Sakayori * add some more tests Signed-off-by: Go Sakayori * add unit test for all functions Signed-off-by: Go Sakayori * remove unecessary header and space Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../path_safety_checker/safety_check.hpp | 69 ++++- .../test/test_safety_check.cpp | 263 ++++++++++++++++-- 2 files changed, 297 insertions(+), 35 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index 56ffd99905579..ab62c369c41e4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -76,9 +76,22 @@ Polygon2d createExtendedPolygon( const PoseWithVelocityAndPolygonStamped & obj_pose_with_poly, const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug); +/** + * @brief Converts path (path with velocity stamped) to predicted path. + * @param path Path. + * @param time_resolution Time resolution. + * @return Predicted path. + */ PredictedPath convertToPredictedPath( const std::vector & path, const double time_resolution); +/** + * @brief Calculates RSS related distance. + * @param front_object_velocity Velocity of front object. + * @param rear_object_velocity Velocity of rear object. + * @param rss_params RSS parameters. + * @return Longitudinal distance. + */ double calcRssDistance( const double front_object_velocity, const double rear_object_velocity, const RSSparams & rss_params); @@ -128,9 +141,29 @@ ExtendedPredictedObjects filterObjectPredictedPathByTimeHorizon( const ExtendedPredictedObjects & objects, const double time_horizon, const bool check_all_predicted_path); +/** + * @brief Filters the path by obtaining points after target pose. + * @param path Path to filter. + * @param target_pose Target pose. + * @return Filtered path. + */ std::vector filterPredictedPathAfterTargetPose( const std::vector & path, const Pose & target_pose); +/** + * @brief Iterate the points in the ego and target's predicted path and + * perform safety check for each of the iterated points using RSS parameters + * @param planned_path The planned path of the ego vehicle. + * @param ego_predicted_path Ego vehicle's predicted path + * @param objects Detected objects. + * @param debug_map Map for collision check debug. + * @param parameters The common parameters used in behavior path planner. + * @param rss_params The parameters used in RSSs + * @param check_all_predicted_path If true, uses all predicted path + * @param hysteresis_factor Hysteresis factor + * @param yaw_difference_th Threshold for yaw difference + * @return True if planned path is safe. + */ bool checkSafetyWithRSS( const PathWithLaneId & planned_path, const std::vector & ego_predicted_path, @@ -144,16 +177,14 @@ bool checkSafetyWithRSS( * perform safety check for each of the iterated points. * @param planned_path The predicted path of the ego vehicle. * @param predicted_ego_path Ego vehicle's predicted path - * @param ego_current_velocity Current velocity of the ego vehicle. * @param target_object The predicted object to check collision with. * @param target_object_path The predicted path of the target object. - * @param common_parameters The common parameters used in behavior path planner. - * @param front_object_deceleration The deceleration of the object in the front.(used in RSS) - * @param rear_object_deceleration The deceleration of the object in the rear.(used in RSS) - * @param yaw_difference_th maximum yaw difference between any given ego path pose and object - * predicted path pose. + * @param common_parameters Common parameters used for behavior path planning. + * @param rss_parameters The parameters used in RSS. + * @param hysteresis_factor Hysteresis factor. + * @param yaw_difference_th Threshold of yaw difference. * @param debug The debug information for collision checking. - * @return true if distance is safe. + * @return True if there is no collision. */ bool checkCollision( const PathWithLaneId & planned_path, @@ -166,16 +197,17 @@ bool checkCollision( /** * @brief Iterate the points in the ego and target's predicted path and * perform safety check for each of the iterated points. - * @param planned_path The predicted path of the ego vehicle. + * @param planned_path The planned path of the ego vehicle. * @param predicted_ego_path Ego vehicle's predicted path - * @param ego_current_velocity Current velocity of the ego vehicle. * @param target_object The predicted object to check collision with. * @param target_object_path The predicted path of the target object. - * @param common_parameters The common parameters used in behavior path planner. - * @param front_object_deceleration The deceleration of the object in the front.(used in RSS) - * @param rear_object_deceleration The deceleration of the object in the rear.(used in RSS) + * @param vehicle_info Ego vehicle information. + * @param rss_parameters The parameters used in RSS. + * @param hysteresis_factor Hysteresis factor. + * @param max_velocity_limit Maximum velocity of ego vehicle. + * @param yaw_difference_th Threshold of yaw difference. * @param debug The debug information for collision checking. - * @return a list of polygon when collision is expected. + * @return List of polygon which collision is expected. */ std::vector get_collided_polygons( const PathWithLaneId & planned_path, @@ -187,6 +219,17 @@ std::vector get_collided_polygons( bool checkPolygonsIntersects( const std::vector & polys_1, const std::vector & polys_2); + +/** + * @brief Checks for safety using integral predicted polygons. + * @param ego_predicted_path The predicted path of ego vehicle. + * @param vehicle_info Information (parameters) about ego vehicle. + * @param objects Surrounding objects. + * @param check_all_predicted_path Whether to check all predicted paths of objects. + * @param params Parameters for integral predicted polygon. + * @param debug_map Map to store debug information. + * @return True if the ego vehicle's path is safe, and false otherwise. + */ bool checkSafetyWithIntegralPredictedPolygon( const std::vector & ego_predicted_path, const VehicleInfo & vehicle_info, const ExtendedPredictedObjects & objects, const bool check_all_predicted_path, diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp index 0d36b2c3fa377..c5694db10f65e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_safety_check.cpp @@ -12,7 +12,6 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_path_planner_common/parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" @@ -22,6 +21,7 @@ #include #include +#include #include #include @@ -29,15 +29,21 @@ #include +#include +#include #include #include constexpr double epsilon = 1e-6; using autoware::behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; +using autoware::behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap; +using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; using autoware::behavior_path_planner::utils::path_safety_checker:: PoseWithVelocityAndPolygonStamped; using autoware::behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; +using autoware::behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; +using autoware::behavior_path_planner::utils::path_safety_checker::RSSparams; using autoware::test_utils::createPose; using autoware::test_utils::generateTrajectory; using autoware::universe_utils::Polygon2d; @@ -45,7 +51,7 @@ using autoware_perception_msgs::msg::Shape; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; -std::vector createTestPath() +std::vector create_test_path() { std::vector path; path.emplace_back(0.0, createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), 1.0); @@ -54,6 +60,69 @@ std::vector createTestPath() return path; } +RSSparams create_rss_parameters( + double longitudinal_velocity_delta_time = 2.0, double rear_vehicle_reaction_time = 1.0, + double rear_vehicle_safety_time_margin = 1.0, double longitudinal_distance_min_threshold = 3.0, + double rear_vehicle_deceleration = -1.0, double front_vehicle_deceleration = -2.0) +{ + RSSparams params; + params.longitudinal_velocity_delta_time = longitudinal_velocity_delta_time; + params.rear_vehicle_reaction_time = rear_vehicle_reaction_time; + params.rear_vehicle_safety_time_margin = rear_vehicle_safety_time_margin; + params.longitudinal_distance_min_threshold = longitudinal_distance_min_threshold; + params.rear_vehicle_deceleration = rear_vehicle_deceleration; + params.front_vehicle_deceleration = front_vehicle_deceleration; + params.extended_polygon_policy = "rectangle"; + + return params; +} + +std::vector create_path_with_velocity_and_polygon( + const Pose initial_pose, const Shape & shape, size_t point_num, double interval, double velocity) +{ + std::vector predicted_path; + predicted_path.reserve(point_num); + Pose pose = initial_pose; + + for (size_t i = 0; i < point_num; i++) { + double time = static_cast(i) * interval; + pose.position.x = initial_pose.position.x + time * velocity; + PoseWithVelocityAndPolygonStamped obj_pose_with_poly( + time, pose, velocity, autoware::universe_utils::toPolygon2d(pose, shape)); + predicted_path.push_back(obj_pose_with_poly); + } + + return predicted_path; +} + +PredictedPathWithPolygon create_predicted_path_with_polygon(Pose pose, float confidence) +{ + PredictedPathWithPolygon path; + Shape shape; + shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + shape.dimensions.x = 1.0; + shape.dimensions.y = 1.0; + path.path = create_path_with_velocity_and_polygon(pose, shape, 10, 1.0, 1.0); + path.confidence = confidence; + + return path; +} + +ExtendedPredictedObject create_extended_predicted_object(Pose pose, float confidence) +{ + ExtendedPredictedObject object; + Shape shape; + shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + shape.dimensions.x = 1.0; + shape.dimensions.y = 1.0; + object.initial_pose = pose; + object.shape = shape; + object.initial_polygon = autoware::universe_utils::toPolygon2d(pose, shape); + object.predicted_paths.push_back(create_predicted_path_with_polygon(pose, confidence)); + + return object; +} + TEST(BehaviorPathPlanningSafetyUtilsTest, isTargetObjectOncoming) { using autoware::behavior_path_planner::utils::path_safety_checker::isTargetObjectOncoming; @@ -228,9 +297,6 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedObjPolygon) CollisionCheckDebug debug; - using autoware::behavior_path_planner::utils::path_safety_checker:: - PoseWithVelocityAndPolygonStamped; - PoseWithVelocityAndPolygonStamped obj_pose_with_poly( 0.0, obj_pose, 0.0, autoware::universe_utils::toPolygon2d(obj_pose, shape)); const auto polygon = @@ -253,22 +319,26 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedObjPolygon) } } +TEST(BehaviorPathPlanningSafetyUtilsTest, convertToPredictedPath) +{ + using autoware::behavior_path_planner::utils::path_safety_checker::convertToPredictedPath; + + auto path = create_test_path(); + double time_resolution = 1.0; + auto predicted_path = convertToPredictedPath(path, time_resolution); + EXPECT_EQ(predicted_path.path.size(), 3); + EXPECT_DOUBLE_EQ(predicted_path.time_step.sec, 1.0); + EXPECT_DOUBLE_EQ(predicted_path.time_step.nanosec, 0.0); +} + TEST(BehaviorPathPlanningSafetyUtilsTest, calcRssDistance) { using autoware::behavior_path_planner::utils::path_safety_checker::calcRssDistance; - using autoware::behavior_path_planner::utils::path_safety_checker::RSSparams; { const double front_vel = 5.0; - const double front_decel = -2.0; const double rear_vel = 10.0; - const double rear_decel = -1.0; - RSSparams params; - params.rear_vehicle_reaction_time = 1.0; - params.rear_vehicle_safety_time_margin = 1.0; - params.longitudinal_distance_min_threshold = 3.0; - params.rear_vehicle_deceleration = rear_decel; - params.front_vehicle_deceleration = front_decel; + auto params = create_rss_parameters(); EXPECT_NEAR(calcRssDistance(front_vel, rear_vel, params), 63.75, epsilon); } @@ -281,9 +351,8 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, calc_minimum_longitudinal_length) double front_object_velocity = 10.0; double rear_object_velocity = 5.0; - autoware::behavior_path_planner::utils::path_safety_checker::RSSparams param; + auto param = create_rss_parameters(); param.longitudinal_distance_min_threshold = 4.0; - param.longitudinal_velocity_delta_time = 2.0; // Condition: front is faster than rear object EXPECT_DOUBLE_EQ( @@ -295,7 +364,7 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, calc_minimum_longitudinal_length) // Basic interpolation test TEST(CalcInterpolatedPoseWithVelocityTest, BasicInterpolation) { - auto path = createTestPath(); + auto path = create_test_path(); auto result = calc_interpolated_pose_with_velocity(path, 0.5); ASSERT_TRUE(result.has_value()); @@ -307,7 +376,7 @@ TEST(CalcInterpolatedPoseWithVelocityTest, BasicInterpolation) // Boundary conditions test TEST(CalcInterpolatedPoseWithVelocityTest, BoundaryConditions) { - auto path = createTestPath(); + auto path = create_test_path(); // First point of the path auto start_result = calc_interpolated_pose_with_velocity(path, 0.0); @@ -330,7 +399,7 @@ TEST(CalcInterpolatedPoseWithVelocityTest, InvalidInput) using autoware::behavior_path_planner::utils::path_safety_checker:: calc_interpolated_pose_with_velocity; - auto path = createTestPath(); + auto path = create_test_path(); // Empty path EXPECT_FALSE(calc_interpolated_pose_with_velocity({}, 1.0).has_value()); @@ -372,13 +441,11 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, get_interpolated_pose_with_velocity_an get_interpolated_pose_with_velocity_and_polygon_stamped; std::vector pred_path; - std::vector pred_path_with_polygon; double current_time = 0.5; autoware::vehicle_info_utils::VehicleInfo vehicle_info{}; vehicle_info.max_longitudinal_offset_m = 1.0; vehicle_info.rear_overhang_m = 1.0; vehicle_info.vehicle_width_m = 2.0; - Shape shape; // Condition: empty path EXPECT_FALSE( @@ -386,12 +453,164 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, get_interpolated_pose_with_velocity_an .has_value()); // Condition: with path - pred_path = createTestPath(); + pred_path = create_test_path(); auto interpolation_result = get_interpolated_pose_with_velocity_and_polygon_stamped(pred_path, current_time, vehicle_info); EXPECT_TRUE(interpolation_result.has_value()); } +TEST(BehaviorPathPlanningSafetyUtilsTest, filterPredictedPathAfterTargetPose) +{ + using autoware::behavior_path_planner::utils::path_safety_checker:: + filterPredictedPathAfterTargetPose; + + auto path = create_test_path(); + Pose pose = createPose(1.0, 0.0, 0.0, 0.0, 0.0, 0.0); + auto filtered_path = filterPredictedPathAfterTargetPose(path, pose); + EXPECT_EQ(filtered_path.size(), 2); + double x_target = 1.0; + for (const auto & pose_with_velocity : filtered_path) { + EXPECT_DOUBLE_EQ(pose_with_velocity.pose.position.x, x_target); + x_target += 1.0; + } +} + +TEST(BehaviorPathPlanningSafetyUtilsTest, checkSafetyWithRSS) +{ + using autoware::behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS; + + auto planned_path = generateTrajectory(3, 1.0); + auto ego_predicted_path = create_test_path(); + autoware::vehicle_info_utils::VehicleInfo vehicle_info{}; + vehicle_info.max_longitudinal_offset_m = 1.0; + vehicle_info.rear_overhang_m = 1.0; + vehicle_info.vehicle_width_m = 2.0; + std::vector objects; + objects.push_back( + create_extended_predicted_object(createPose(10.0, 8.0, 0.0, 0.0, 0.0, 0.0), 0.5)); + objects.push_back( + create_extended_predicted_object(createPose(0.0, 1.0, 0.0, 0.0, 0.0, 0.0), 0.6)); + CollisionCheckDebugMap debug_map; + BehaviorPathPlannerParameters parameters; + parameters.vehicle_info = vehicle_info; + auto rss_params = create_rss_parameters(); + double hysteresis_factor = 1.0; + const double yaw_difference_th = M_PI_2; + + EXPECT_FALSE(checkSafetyWithRSS( + planned_path, ego_predicted_path, objects, debug_map, parameters, rss_params, true, + hysteresis_factor, yaw_difference_th)); + objects.pop_back(); + EXPECT_TRUE(checkSafetyWithRSS( + planned_path, ego_predicted_path, objects, debug_map, parameters, rss_params, true, + hysteresis_factor, yaw_difference_th)); +} + +TEST(BehaviorPathPlanningSafetyUtilsTest, checkSafetyWithIntegralPredictedPolygon) +{ + using autoware::behavior_path_planner::utils::path_safety_checker:: + checkSafetyWithIntegralPredictedPolygon; + + auto ego_predicted_path = create_test_path(); + autoware::vehicle_info_utils::VehicleInfo vehicle_info{}; + vehicle_info.max_longitudinal_offset_m = 1.0; + vehicle_info.rear_overhang_m = 1.0; + vehicle_info.vehicle_width_m = 2.0; + autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects objects; + objects.push_back( + create_extended_predicted_object(createPose(10.0, 8.0, 0.0, 0.0, 0.0, 0.0), 0.5)); + objects.push_back( + create_extended_predicted_object(createPose(0.0, 1.0, 0.0, 0.0, 0.0, 0.0), 0.6)); + + autoware::behavior_path_planner::utils::path_safety_checker::IntegralPredictedPolygonParams + params{1.0, 1.0, 1.0, 2.0}; + CollisionCheckDebugMap debug_map; + + EXPECT_FALSE(checkSafetyWithIntegralPredictedPolygon( + ego_predicted_path, vehicle_info, objects, true, params, debug_map)); + + objects.pop_back(); + EXPECT_TRUE(checkSafetyWithIntegralPredictedPolygon( + ego_predicted_path, vehicle_info, objects, true, params, debug_map)); +} + +TEST(BehaviorPathPlanningSafetyUtilsTest, checkCollision) +{ + using autoware::behavior_path_planner::utils::path_safety_checker::checkCollision; + using autoware::behavior_path_planner::utils::path_safety_checker::get_collided_polygons; + + auto planned_path = autoware::test_utils::generateTrajectory(3, 1.0); + auto predicted_ego_path = create_test_path(); + + ExtendedPredictedObject target_object; + target_object.initial_pose = createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); + Shape shape; + shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + shape.dimensions.x = 2.0; + shape.dimensions.y = 2.0; + auto object_path = + create_predicted_path_with_polygon(createPose(0.0, 1.0, 0.0, 0.0, 0.0, 0.0), 1.0); + + autoware::vehicle_info_utils::VehicleInfo vehicle_info; + vehicle_info.max_longitudinal_offset_m = 4.0; + vehicle_info.vehicle_width_m = 2.0; + vehicle_info.rear_overhang_m = 1.0; + BehaviorPathPlannerParameters common_parameters; + common_parameters.vehicle_info = vehicle_info; + + auto rss_parameters = create_rss_parameters(); + double hysteresis_factor = 1.0; + double max_velocity_limit = 10.0; + const double yaw_difference_th = M_PI_2; + CollisionCheckDebug debug; + + { + EXPECT_FALSE(checkCollision( + planned_path, predicted_ego_path, target_object, object_path, common_parameters, + rss_parameters, hysteresis_factor, yaw_difference_th, debug)); + auto collide_polygon = get_collided_polygons( + planned_path, predicted_ego_path, target_object, object_path, vehicle_info, rss_parameters, + hysteresis_factor, max_velocity_limit, yaw_difference_th, debug); + EXPECT_EQ(collide_polygon.size(), 3); + } + { + target_object.initial_pose = createPose(0.0, 4.0, 0.0, 0.0, 0.0, 0.0); + object_path = create_predicted_path_with_polygon(createPose(0.0, 4.0, 0.0, 0.0, 0.0, 0.0), 1.0); + auto collide_polygon = get_collided_polygons( + planned_path, predicted_ego_path, target_object, object_path, vehicle_info, rss_parameters, + hysteresis_factor, max_velocity_limit, yaw_difference_th, debug); + EXPECT_TRUE(checkCollision( + planned_path, predicted_ego_path, target_object, object_path, common_parameters, + rss_parameters, hysteresis_factor, yaw_difference_th, debug)); + EXPECT_TRUE(collide_polygon.empty()); + } + { + target_object.initial_pose = createPose(10.0, 4.0, 0.0, 0.0, 0.0, 0.0); + object_path = + create_predicted_path_with_polygon(createPose(10.0, 4.0, 0.0, 0.0, 0.0, 0.0), 1.0); + EXPECT_TRUE(checkCollision( + planned_path, predicted_ego_path, target_object, object_path, common_parameters, + rss_parameters, hysteresis_factor, yaw_difference_th, debug)); + auto collide_polygon = get_collided_polygons( + planned_path, predicted_ego_path, target_object, object_path, vehicle_info, rss_parameters, + hysteresis_factor, max_velocity_limit, yaw_difference_th, debug); + EXPECT_TRUE(collide_polygon.empty()); + } + { + rss_parameters.extended_polygon_policy = "along_path"; + target_object.initial_pose = createPose(10.0, 4.0, 0.0, 0.0, 0.0, 0.0); + object_path = + create_predicted_path_with_polygon(createPose(10.0, 4.0, 0.0, 0.0, 0.0, 0.0), 1.0); + EXPECT_TRUE(checkCollision( + planned_path, predicted_ego_path, target_object, object_path, common_parameters, + rss_parameters, hysteresis_factor, yaw_difference_th, debug)); + auto collide_polygon = get_collided_polygons( + planned_path, predicted_ego_path, target_object, object_path, vehicle_info, rss_parameters, + hysteresis_factor, max_velocity_limit, yaw_difference_th, debug); + EXPECT_TRUE(collide_polygon.empty()); + } +} + TEST(BehaviorPathPlanningSafetyUtilsTest, checkPolygonsIntersects) { using autoware::behavior_path_planner::utils::path_safety_checker::checkPolygonsIntersects; From a7cc44d91ba1ce1b572349db3b8b4f74bed64b9a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 19 Nov 2024 21:23:47 +0900 Subject: [PATCH 052/273] feat: suppress warning/error of the empty predicted trajectory by MPC (#9373) Signed-off-by: Takayuki Murooka --- .../autoware_control_validator/src/control_validator.cpp | 4 +--- .../lane_departure_checker_node.cpp | 3 +-- control/autoware_mpc_lateral_controller/README.md | 6 ++++++ 3 files changed, 8 insertions(+), 5 deletions(-) diff --git a/control/autoware_control_validator/src/control_validator.cpp b/control/autoware_control_validator/src/control_validator.cpp index 796928519e8d1..d51282cb33bb3 100644 --- a/control/autoware_control_validator/src/control_validator.cpp +++ b/control/autoware_control_validator/src/control_validator.cpp @@ -191,9 +191,7 @@ void ControlValidator::validate( const Odometry & kinematics) { if (predicted_trajectory.points.size() < 2) { - RCLCPP_ERROR_THROTTLE( - get_logger(), *get_clock(), 1000, - "predicted_trajectory size is less than 2. Cannot validate."); + RCLCPP_DEBUG(get_logger(), "predicted_trajectory size is less than 2. Cannot validate."); return; } if (reference_trajectory.points.size() < 2) { diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp index 8d954517f552d..366b84a1f6131 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp @@ -252,8 +252,7 @@ bool LaneDepartureCheckerNode::isDataValid() } if (predicted_trajectory_->points.empty()) { - RCLCPP_ERROR_THROTTLE( - get_logger(), *get_clock(), 5000, "predicted_trajectory is empty. Not expected!"); + RCLCPP_DEBUG(get_logger(), "predicted_trajectory is empty. Not expected!"); return false; } diff --git a/control/autoware_mpc_lateral_controller/README.md b/control/autoware_mpc_lateral_controller/README.md index 1b3af44343208..7585e7db140b3 100644 --- a/control/autoware_mpc_lateral_controller/README.md +++ b/control/autoware_mpc_lateral_controller/README.md @@ -75,6 +75,12 @@ Return LateralOutput which contains the following to the controller node - LateralSyncData - steer angle convergence +Publish the following messages. + +| Name | Type | Description | +| ------------------------------- | ---------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `~/output/predicted_trajectory` | autoware_planning_msgs::Trajectory | Predicted trajectory calculated by MPC. The trajectory size will be empty when the controller is in an emergency such as too large deviation from the planning trajectory. | + ### MPC class The `MPC` class (defined in `mpc.hpp`) provides the interface with the MPC algorithm. From de9d9cbc493cf954cceb2308188990672ef2a972 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 19 Nov 2024 22:15:35 +0900 Subject: [PATCH 053/273] fix(autoware_mpc_lateral_controller): fix variableScope (#9390) Signed-off-by: Ryuta Kambe --- control/autoware_mpc_lateral_controller/src/mpc.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 2d2179bb41a84..94af6bfd61e8a 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -511,7 +511,6 @@ MPCMatrix MPC::generateMPCMatrix( // update mpc matrix int idx_x_i = i * DIM_X; - int idx_x_i_prev = (i - 1) * DIM_X; int idx_u_i = i * DIM_U; int idx_y_i = i * DIM_Y; if (i == 0) { @@ -519,6 +518,7 @@ MPCMatrix MPC::generateMPCMatrix( m.Bex.block(0, 0, DIM_X, DIM_U) = Bd; m.Wex.block(0, 0, DIM_X, 1) = Wd; } else { + int idx_x_i_prev = (i - 1) * DIM_X; m.Aex.block(idx_x_i, 0, DIM_X, DIM_X) = Ad * m.Aex.block(idx_x_i_prev, 0, DIM_X, DIM_X); for (int j = 0; j < i; ++j) { int idx_u_j = j * DIM_U; From 3a1ae3bdba64bf7cf5f4a36eb48de07a7ca025e7 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 20 Nov 2024 00:00:23 +0900 Subject: [PATCH 054/273] feat(mpc_lateral_controller): suppress rclcpp_warning/error (#9382) * feat(mpc_lateral_controller): suppress rclcpp_warning/error Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * fix test Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../CMakeLists.txt | 2 + .../autoware/mpc_lateral_controller/mpc.hpp | 14 +++-- .../mpc_lateral_controller.hpp | 2 +- .../src/mpc.cpp | 63 +++++++++---------- .../src/mpc_lateral_controller.cpp | 25 ++++---- .../test/test_mpc.cpp | 44 ++++++++----- .../src/controller_node.cpp | 2 + 7 files changed, 86 insertions(+), 66 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/CMakeLists.txt b/control/autoware_mpc_lateral_controller/CMakeLists.txt index dff85d70419a1..b03fa84e4b116 100644 --- a/control/autoware_mpc_lateral_controller/CMakeLists.txt +++ b/control/autoware_mpc_lateral_controller/CMakeLists.txt @@ -4,6 +4,8 @@ project(autoware_mpc_lateral_controller) find_package(autoware_cmake REQUIRED) autoware_package() +find_package(fmt REQUIRED) + ament_auto_add_library(steering_offset_lib SHARED src/steering_offset/steering_offset.cpp ) diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp index 0e4691822326f..eedac39f37bd4 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp @@ -191,6 +191,12 @@ struct MPCMatrix MPCMatrix() = default; }; +struct ResultWithReason +{ + bool result{false}; + std::string reason{""}; +}; + /** * MPC-based waypoints follower class * @brief calculate control command to follow reference waypoints @@ -232,7 +238,7 @@ class MPC * @param current_kinematics The current vehicle kinematics. * @return A pair of a boolean flag indicating success and the MPC data. */ - std::pair getData( + std::pair getData( const MPCTrajectory & trajectory, const SteeringReport & current_steer, const Odometry & current_kinematics); @@ -272,7 +278,7 @@ class MPC * @param [in] current_velocity current ego velocity * @return A pair of a boolean flag indicating success and the optimized input vector. */ - std::pair executeOptimization( + std::pair executeOptimization( const MPCMatrix & mpc_matrix, const VectorXd & x0, const double prediction_dt, const MPCTrajectory & trajectory, const double current_velocity); @@ -283,7 +289,7 @@ class MPC * @param input The input trajectory. * @return A pair of a boolean flag indicating success and the resampled trajectory. */ - std::pair resampleMPCTrajectoryByTime( + std::pair resampleMPCTrajectoryByTime( const double start_time, const double prediction_dt, const MPCTrajectory & input) const; /** @@ -450,7 +456,7 @@ class MPC * @param diagnostic Diagnostic data for debugging purposes. * @return True if the MPC calculation is successful, false otherwise. */ - bool calculateMPC( + ResultWithReason calculateMPC( const SteeringReport & current_steer, const Odometry & current_kinematics, Lateral & ctrl_cmd, Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic, LateralHorizon & ctrl_cmd_horizon); diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp index aca0f0ccbc814..fe68d150b5b9a 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -96,7 +96,7 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase bool m_keep_steer_control_until_converged; // MPC solver checker. - bool m_is_mpc_solved{true}; + ResultWithReason m_mpc_solved_status{true}; // trajectory buffer for detecting new trajectory std::deque m_trajectory_buffer; diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 94af6bfd61e8a..3c3496080b597 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -20,6 +20,8 @@ #include "autoware/universe_utils/math/unit_conversion.hpp" #include "rclcpp/rclcpp.hpp" +#include + #include #include @@ -37,7 +39,7 @@ MPC::MPC(rclcpp::Node & node) node.create_publisher("~/debug/resampled_reference_trajectory", rclcpp::QoS(1)); } -bool MPC::calculateMPC( +ResultWithReason MPC::calculateMPC( const SteeringReport & current_steer, const Odometry & current_kinematics, Lateral & ctrl_cmd, Trajectory & predicted_trajectory, Float32MultiArrayStamped & diagnostic, LateralHorizon & ctrl_cmd_horizon) @@ -48,10 +50,10 @@ bool MPC::calculateMPC( applyVelocityDynamicsFilter(m_reference_trajectory, current_kinematics); // get the necessary data - const auto [success_data, mpc_data] = + const auto [get_data_result, mpc_data] = getData(reference_trajectory, current_steer, current_kinematics); - if (!success_data) { - return fail_warn_throttle("fail to get MPC Data. Stop MPC."); + if (!get_data_result.result) { + return ResultWithReason{false, fmt::format("getting MPC Data ({}).", get_data_result.reason)}; } // calculate initial state of the error dynamics @@ -61,7 +63,7 @@ bool MPC::calculateMPC( const auto [success_delay, x0_delayed] = updateStateForDelayCompensation(reference_trajectory, mpc_data.nearest_time, x0); if (!success_delay) { - return fail_warn_throttle("delay compensation failed. Stop MPC."); + return ResultWithReason{false, "delay compensation."}; } // resample reference trajectory with mpc sampling time @@ -69,21 +71,22 @@ bool MPC::calculateMPC( const double prediction_dt = getPredictionDeltaTime(mpc_start_time, reference_trajectory, current_kinematics); - const auto [success_resample, mpc_resampled_ref_trajectory] = + const auto [resample_result, mpc_resampled_ref_trajectory] = resampleMPCTrajectoryByTime(mpc_start_time, prediction_dt, reference_trajectory); - if (!success_resample) { - return fail_warn_throttle("trajectory resampling failed. Stop MPC."); + if (!resample_result.result) { + return ResultWithReason{ + false, fmt::format("trajectory resampling ({}).", resample_result.reason)}; } // generate mpc matrix : predict equation Xec = Aex * x0 + Bex * Uex + Wex const auto mpc_matrix = generateMPCMatrix(mpc_resampled_ref_trajectory, prediction_dt); // solve Optimization problem - const auto [success_opt, Uex] = executeOptimization( + const auto [opt_result, Uex] = executeOptimization( mpc_matrix, x0_delayed, prediction_dt, mpc_resampled_ref_trajectory, current_kinematics.twist.twist.linear.x); - if (!success_opt) { - return fail_warn_throttle("optimization failed. Stop MPC."); + if (!opt_result.result) { + return ResultWithReason{false, fmt::format("optimization failure ({}).", opt_result.reason)}; } // apply filters for the input limitation and low pass filter @@ -138,7 +141,7 @@ bool MPC::calculateMPC( ctrl_cmd_horizon.controls.push_back(lateral); } - return true; + return ResultWithReason{true}; } Float32MultiArrayStamped MPC::generateDiagData( @@ -278,7 +281,7 @@ void MPC::resetPrevResult(const SteeringReport & current_steer) m_raw_steer_cmd_pprev = std::clamp(current_steer.steering_tire_angle, -steer_lim_f, steer_lim_f); } -std::pair MPC::getData( +std::pair MPC::getData( const MPCTrajectory & traj, const SteeringReport & current_steer, const Odometry & current_kinematics) { @@ -288,8 +291,7 @@ std::pair MPC::getData( if (!MPCUtils::calcNearestPoseInterp( traj, current_pose, &(data.nearest_pose), &(data.nearest_idx), &(data.nearest_time), ego_nearest_dist_threshold, ego_nearest_yaw_threshold)) { - warn_throttle("calculateMPC: error in calculating nearest pose. stop mpc."); - return {false, MPCData{}}; + return {ResultWithReason{false, "error in calculating nearest pose"}, MPCData{}}; } // get data @@ -304,14 +306,12 @@ std::pair MPC::getData( // check error limit const double dist_err = calcDistance2d(current_pose, data.nearest_pose); if (dist_err > m_admissible_position_error) { - warn_throttle("Too large position error: %fm > %fm", dist_err, m_admissible_position_error); - return {false, MPCData{}}; + return {ResultWithReason{false, "too large position error"}, MPCData{}}; } // check yaw error limit if (std::fabs(data.yaw_err) > m_admissible_yaw_error_rad) { - warn_throttle("Too large yaw error: %f > %f", data.yaw_err, m_admissible_yaw_error_rad); - return {false, MPCData{}}; + return {ResultWithReason{false, "too large yaw error"}, MPCData{}}; } // check trajectory time length @@ -319,13 +319,12 @@ std::pair MPC::getData( m_param.min_prediction_length / static_cast(m_param.prediction_horizon - 1); auto end_time = data.nearest_time + m_param.input_delay + m_ctrl_period + max_prediction_time; if (end_time > traj.relative_time.back()) { - warn_throttle("path is too short for prediction."); - return {false, MPCData{}}; + return {ResultWithReason{false, "path is too short for prediction."}, MPCData{}}; } - return {true, data}; + return {ResultWithReason{true}, data}; } -std::pair MPC::resampleMPCTrajectoryByTime( +std::pair MPC::resampleMPCTrajectoryByTime( const double ts, const double prediction_dt, const MPCTrajectory & input) const { MPCTrajectory output; @@ -334,8 +333,7 @@ std::pair MPC::resampleMPCTrajectoryByTime( mpc_time_v.push_back(ts + i * prediction_dt); } if (!MPCUtils::linearInterpMPCTrajectory(input.relative_time, input, mpc_time_v, output)) { - warn_throttle("calculateMPC: mpc resample error. stop mpc calculation. check code!"); - return {false, {}}; + return {ResultWithReason{false, "mpc resample error"}, {}}; } // Publish resampled reference trajectory for debug purpose. if (m_publish_debug_trajectories) { @@ -344,7 +342,7 @@ std::pair MPC::resampleMPCTrajectoryByTime( converted_output.header.frame_id = "map"; m_debug_resampled_reference_trajectory_pub->publish(converted_output); } - return {true, output}; + return {ResultWithReason{true}, output}; } VectorXd MPC::getInitialState(const MPCData & data) @@ -577,15 +575,14 @@ MPCMatrix MPC::generateMPCMatrix( * ~~~ * [ -au_lim * dt ] < [uN-uN-1] < [ au_lim * dt ] (*N... DIM_U) */ -std::pair MPC::executeOptimization( +std::pair MPC::executeOptimization( const MPCMatrix & m, const VectorXd & x0, const double prediction_dt, const MPCTrajectory & traj, const double current_velocity) { VectorXd Uex; if (!isValid(m)) { - warn_throttle("model matrix is invalid. stop MPC."); - return {false, {}}; + return {ResultWithReason{false, "invalid model matrix"}, {}}; } const int DIM_U_N = m_param.prediction_horizon * m_vehicle_model_ptr->getDimU(); @@ -622,8 +619,7 @@ std::pair MPC::executeOptimization( bool solve_result = m_qpsolver_ptr->solve(H, f.transpose(), A, lb, ub, lbA, ubA, Uex); auto t_end = std::chrono::system_clock::now(); if (!solve_result) { - warn_throttle("qp solver error"); - return {false, {}}; + return {ResultWithReason{false, "qp solver error"}, {}}; } { @@ -632,10 +628,9 @@ std::pair MPC::executeOptimization( } if (Uex.array().isNaN().any()) { - warn_throttle("model Uex includes NaN, stop MPC."); - return {false, {}}; + return {ResultWithReason{false, "model Uex including NaN"}, {}}; } - return {true, Uex}; + return {ResultWithReason{true}, Uex}; } void MPC::addSteerWeightR(const double prediction_dt, MatrixXd & R) const diff --git a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp index 7998aafd8cb4f..76e5b4737e418 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp @@ -235,20 +235,17 @@ std::shared_ptr MpcLateralController::createSteerOffset void MpcLateralController::setStatus(diagnostic_updater::DiagnosticStatusWrapper & stat) { - if (m_is_mpc_solved) { + if (m_mpc_solved_status.result) { stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "MPC succeeded."); } else { - const std::string error_msg = "The MPC solver failed. Call MRM to stop the car."; + const std::string error_msg = "MPC failed due to " + m_mpc_solved_status.reason; stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, error_msg); } } void MpcLateralController::setupDiag() { - auto & d = diag_updater_; - d->setHardwareID("mpc_lateral_controller"); - - d->add("MPC_solve_checker", [&](auto & stat) { setStatus(stat); }); + diag_updater_->add("MPC_solve_checker", [&](auto & stat) { setStatus(stat); }); } trajectory_follower::LateralOutput MpcLateralController::run( @@ -277,11 +274,16 @@ trajectory_follower::LateralOutput MpcLateralController::run( } trajectory_follower::LateralHorizon ctrl_cmd_horizon{}; - const bool is_mpc_solved = m_mpc->calculateMPC( + const auto mpc_solved_status = m_mpc->calculateMPC( m_current_steering, m_current_kinematic_state, ctrl_cmd, predicted_traj, debug_values, ctrl_cmd_horizon); - m_is_mpc_solved = is_mpc_solved; // for diagnostic updater + if ( + (m_mpc_solved_status.result == true && mpc_solved_status.result == false) || + (!mpc_solved_status.result && mpc_solved_status.reason != m_mpc_solved_status.reason)) { + RCLCPP_ERROR(logger_, "MPC failed due to %s", mpc_solved_status.reason.c_str()); + } + m_mpc_solved_status = mpc_solved_status; // for diagnostic updater diag_updater_->force_update(); @@ -290,7 +292,7 @@ trajectory_follower::LateralOutput MpcLateralController::run( // the vehicle will return to the path by re-planning the trajectory or external operation. // After the recovery, the previous value of the optimization may deviate greatly from // the actual steer angle, and it may make the optimization result unstable. - if (!is_mpc_solved || !is_under_control) { + if (!mpc_solved_status.result || !is_under_control) { m_mpc->resetPrevResult(m_current_steering); } else { setSteeringToHistory(ctrl_cmd); @@ -334,13 +336,12 @@ trajectory_follower::LateralOutput MpcLateralController::run( return createLateralOutput(m_ctrl_cmd_prev, false, ctrl_cmd_horizon); } - if (!is_mpc_solved) { - warn_throttle("MPC is not solved. publish 0 velocity."); + if (!mpc_solved_status.result) { ctrl_cmd = getStopControlCommand(); } m_ctrl_cmd_prev = ctrl_cmd; - return createLateralOutput(ctrl_cmd, is_mpc_solved, ctrl_cmd_horizon); + return createLateralOutput(ctrl_cmd, mpc_solved_status.result, ctrl_cmd_horizon); } bool MpcLateralController::isSteerConverged(const Lateral & cmd) const diff --git a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp index fe2ca8d451018..ccc91d0e7751b 100644 --- a/control/autoware_mpc_lateral_controller/test/test_mpc.cpp +++ b/control/autoware_mpc_lateral_controller/test/test_mpc.cpp @@ -214,7 +214,8 @@ TEST_F(MPCTest, InitializeAndCalculate) Float32MultiArrayStamped diag; LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); @@ -250,7 +251,8 @@ TEST_F(MPCTest, InitializeAndCalculateRightTurn) Float32MultiArrayStamped diag; LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); @@ -281,7 +283,8 @@ TEST_F(MPCTest, OsqpCalculate) Float32MultiArrayStamped diag; LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - EXPECT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + EXPECT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); @@ -313,7 +316,8 @@ TEST_F(MPCTest, OsqpCalculateRightTurn) Float32MultiArrayStamped diag; LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); @@ -347,7 +351,8 @@ TEST_F(MPCTest, KinematicsNoDelayCalculate) Float32MultiArrayStamped diag; LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); @@ -382,7 +387,8 @@ TEST_F(MPCTest, KinematicsNoDelayCalculateRightTurn) Float32MultiArrayStamped diag; LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_LT(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_LT(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); @@ -411,7 +417,8 @@ TEST_F(MPCTest, DynamicCalculate) Float32MultiArrayStamped diag; LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); @@ -440,28 +447,32 @@ TEST_F(MPCTest, MultiSolveWithBuffer) LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_zero, default_velocity); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); EXPECT_EQ(ctrl_cmd_horizon.controls.size(), param.prediction_horizon); EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f); - ASSERT_TRUE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + ASSERT_TRUE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); EXPECT_EQ(ctrl_cmd.steering_tire_angle, 0.0f); EXPECT_EQ(ctrl_cmd.steering_tire_rotation_rate, 0.0f); EXPECT_EQ(mpc->m_input_buffer.size(), size_t(3)); @@ -492,11 +503,14 @@ TEST_F(MPCTest, FailureCases) Float32MultiArrayStamped diag; LateralHorizon ctrl_cmd_horizon; const auto odom = makeOdometry(pose_far, default_velocity); - EXPECT_FALSE(mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon)); + EXPECT_FALSE( + mpc->calculateMPC(neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result); // Calculate MPC with a fast velocity to make the prediction go further than the reference path - EXPECT_FALSE(mpc->calculateMPC( - neutral_steer, makeOdometry(pose_far, default_velocity + 10.0), ctrl_cmd, pred_traj, diag, - ctrl_cmd_horizon)); + EXPECT_FALSE(mpc + ->calculateMPC( + neutral_steer, makeOdometry(pose_far, default_velocity + 10.0), ctrl_cmd, + pred_traj, diag, ctrl_cmd_horizon) + .result); } } // namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/autoware_trajectory_follower_node/src/controller_node.cpp b/control/autoware_trajectory_follower_node/src/controller_node.cpp index f4a32444afe9d..d3fc1ba52c95c 100644 --- a/control/autoware_trajectory_follower_node/src/controller_node.cpp +++ b/control/autoware_trajectory_follower_node/src/controller_node.cpp @@ -62,6 +62,8 @@ Controller::Controller(const rclcpp::NodeOptions & node_options) : Node("control enable_control_cmd_horizon_pub_ = declare_parameter("enable_control_cmd_horizon_pub", false); + diag_updater_->setHardwareID("trajectory_follower_node"); + const auto lateral_controller_mode = getLateralControllerMode(declare_parameter("lateral_controller_mode")); switch (lateral_controller_mode) { From f22096a4ffb75ac8f0a315ac0496aad781fb8166 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 20 Nov 2024 09:20:57 +0900 Subject: [PATCH 055/273] fix(autoware_obstacle_stop_planner): fix cppcheck warnings (#9388) Signed-off-by: Ryuta Kambe --- .../src/adaptive_cruise_control.cpp | 14 ++------------ .../src/adaptive_cruise_control.hpp | 4 ++-- .../src/debug_marker.hpp | 2 +- 3 files changed, 5 insertions(+), 15 deletions(-) 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 ee2eadac6f780..82a4d5a7ec550 100644 --- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp +++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.cpp @@ -111,16 +111,6 @@ double getDistanceFromTwoPoint( } } -constexpr double sign(const double value) -{ - if (value > 0) { - return 1.0; - } else if (value < 0) { - return -1.0; - } else { - return 0.0; - } -} } // namespace namespace autoware::motion_planning @@ -573,7 +563,7 @@ double AdaptiveCruiseController::calcUpperVelocity( } double AdaptiveCruiseController::calcThreshDistToForwardObstacle( - const double current_vel, const double obj_vel) + const double current_vel, const double obj_vel) const { const double current_vel_min = std::max(1.0, std::fabs(current_vel)); const double obj_vel_min = std::max(0.0, obj_vel); @@ -590,7 +580,7 @@ double AdaptiveCruiseController::calcThreshDistToForwardObstacle( } double AdaptiveCruiseController::calcBaseDistToForwardObstacle( - const double current_vel, const double obj_vel) + const double current_vel, const double obj_vel) const { const double obj_vel_min = std::max(0.0, obj_vel); const double minimum_distance = param_.min_dist_standard; 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 7535986f1db85..ce57f585197ad 100644 --- a/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp +++ b/planning/autoware_obstacle_stop_planner/src/adaptive_cruise_control.hpp @@ -203,8 +203,8 @@ class AdaptiveCruiseController double estimateRoughPointVelocity(double current_vel); bool isObstacleVelocityHigh(const double obj_vel); 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 calcThreshDistToForwardObstacle(const double current_vel, const double obj_vel) const; + double calcBaseDistToForwardObstacle(const double current_vel, const double obj_vel) const; 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); diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp index ac043dd895ea7..4400368cc3d70 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp @@ -77,7 +77,7 @@ class DebugValues * @brief get all the debug values as an std::array * @return array of all debug values */ - std::array(TYPE::SIZE)> getValues() const { return values_; } + const std::array(TYPE::SIZE)> & getValues() const { return values_; } /** * @brief set the given type to the given value * @param [in] type TYPE of the value From be8235d785597c41d01782ec35da862ba0906578 Mon Sep 17 00:00:00 2001 From: Yutaka Kondo Date: Wed, 20 Nov 2024 10:46:29 +0900 Subject: [PATCH 056/273] refactor(sensing): move CUDA related packages to `sensing/cuda` directory (#9369) move to cuda dir Signed-off-by: Yutaka Kondo --- sensing/{ => cuda}/autoware_cuda_utils/CHANGELOG.rst | 0 sensing/{ => cuda}/autoware_cuda_utils/CMakeLists.txt | 0 sensing/{ => cuda}/autoware_cuda_utils/README.md | 0 .../include/autoware/cuda_utils/cuda_check_error.hpp | 0 .../include/autoware/cuda_utils/cuda_unique_ptr.hpp | 0 .../include/autoware/cuda_utils/stream_unique_ptr.hpp | 0 sensing/{ => cuda}/autoware_cuda_utils/package.xml | 0 7 files changed, 0 insertions(+), 0 deletions(-) rename sensing/{ => cuda}/autoware_cuda_utils/CHANGELOG.rst (100%) rename sensing/{ => cuda}/autoware_cuda_utils/CMakeLists.txt (100%) rename sensing/{ => cuda}/autoware_cuda_utils/README.md (100%) rename sensing/{ => cuda}/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp (100%) rename sensing/{ => cuda}/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp (100%) rename sensing/{ => cuda}/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp (100%) rename sensing/{ => cuda}/autoware_cuda_utils/package.xml (100%) diff --git a/sensing/autoware_cuda_utils/CHANGELOG.rst b/sensing/cuda/autoware_cuda_utils/CHANGELOG.rst similarity index 100% rename from sensing/autoware_cuda_utils/CHANGELOG.rst rename to sensing/cuda/autoware_cuda_utils/CHANGELOG.rst diff --git a/sensing/autoware_cuda_utils/CMakeLists.txt b/sensing/cuda/autoware_cuda_utils/CMakeLists.txt similarity index 100% rename from sensing/autoware_cuda_utils/CMakeLists.txt rename to sensing/cuda/autoware_cuda_utils/CMakeLists.txt diff --git a/sensing/autoware_cuda_utils/README.md b/sensing/cuda/autoware_cuda_utils/README.md similarity index 100% rename from sensing/autoware_cuda_utils/README.md rename to sensing/cuda/autoware_cuda_utils/README.md diff --git a/sensing/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp b/sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp similarity index 100% rename from sensing/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp rename to sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp diff --git a/sensing/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp b/sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp similarity index 100% rename from sensing/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp rename to sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp diff --git a/sensing/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp b/sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp similarity index 100% rename from sensing/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp rename to sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp diff --git a/sensing/autoware_cuda_utils/package.xml b/sensing/cuda/autoware_cuda_utils/package.xml similarity index 100% rename from sensing/autoware_cuda_utils/package.xml rename to sensing/cuda/autoware_cuda_utils/package.xml From e9017515ab29571e772b160316ddd259a237353e Mon Sep 17 00:00:00 2001 From: Yutaka Kondo Date: Wed, 20 Nov 2024 11:47:47 +0900 Subject: [PATCH 057/273] Revert "refactor(sensing): move CUDA related packages to `sensing/cuda` directory" (#9394) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Revert "refactor(sensing): move CUDA related packages to `sensing/cuda` direc…" This reverts commit be8235d785597c41d01782ec35da862ba0906578. --- sensing/{cuda => }/autoware_cuda_utils/CHANGELOG.rst | 0 sensing/{cuda => }/autoware_cuda_utils/CMakeLists.txt | 0 sensing/{cuda => }/autoware_cuda_utils/README.md | 0 .../include/autoware/cuda_utils/cuda_check_error.hpp | 0 .../include/autoware/cuda_utils/cuda_unique_ptr.hpp | 0 .../include/autoware/cuda_utils/stream_unique_ptr.hpp | 0 sensing/{cuda => }/autoware_cuda_utils/package.xml | 0 7 files changed, 0 insertions(+), 0 deletions(-) rename sensing/{cuda => }/autoware_cuda_utils/CHANGELOG.rst (100%) rename sensing/{cuda => }/autoware_cuda_utils/CMakeLists.txt (100%) rename sensing/{cuda => }/autoware_cuda_utils/README.md (100%) rename sensing/{cuda => }/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp (100%) rename sensing/{cuda => }/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp (100%) rename sensing/{cuda => }/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp (100%) rename sensing/{cuda => }/autoware_cuda_utils/package.xml (100%) diff --git a/sensing/cuda/autoware_cuda_utils/CHANGELOG.rst b/sensing/autoware_cuda_utils/CHANGELOG.rst similarity index 100% rename from sensing/cuda/autoware_cuda_utils/CHANGELOG.rst rename to sensing/autoware_cuda_utils/CHANGELOG.rst diff --git a/sensing/cuda/autoware_cuda_utils/CMakeLists.txt b/sensing/autoware_cuda_utils/CMakeLists.txt similarity index 100% rename from sensing/cuda/autoware_cuda_utils/CMakeLists.txt rename to sensing/autoware_cuda_utils/CMakeLists.txt diff --git a/sensing/cuda/autoware_cuda_utils/README.md b/sensing/autoware_cuda_utils/README.md similarity index 100% rename from sensing/cuda/autoware_cuda_utils/README.md rename to sensing/autoware_cuda_utils/README.md diff --git a/sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp b/sensing/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp similarity index 100% rename from sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp rename to sensing/autoware_cuda_utils/include/autoware/cuda_utils/cuda_check_error.hpp diff --git a/sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp b/sensing/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp similarity index 100% rename from sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp rename to sensing/autoware_cuda_utils/include/autoware/cuda_utils/cuda_unique_ptr.hpp diff --git a/sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp b/sensing/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp similarity index 100% rename from sensing/cuda/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp rename to sensing/autoware_cuda_utils/include/autoware/cuda_utils/stream_unique_ptr.hpp diff --git a/sensing/cuda/autoware_cuda_utils/package.xml b/sensing/autoware_cuda_utils/package.xml similarity index 100% rename from sensing/cuda/autoware_cuda_utils/package.xml rename to sensing/autoware_cuda_utils/package.xml From 8ce9f583c0a3fc6d92f7921273d50ab9f960e577 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 13:09:05 +0900 Subject: [PATCH 058/273] fix(autoware_occupancy_grid_map_outlier_filter): fix bugprone-incorrect-roundings (#9217) * fix: bugprone-incorrect-roundings Signed-off-by: kobayu858 * fix: clang-format Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/occupancy_grid_map_outlier_filter_node.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp b/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp index cf8e36833b339..eb52b903b90ca 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp +++ b/perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp @@ -32,6 +32,7 @@ #endif #include +#include #include #include #include @@ -140,7 +141,8 @@ void RadiusSearch2dFilter::filter( const float distance = std::hypot(xy_cloud->points[i].x - pose.position.x, xy_cloud->points[i].y - pose.position.y); const int min_points_threshold = std::min( - std::max(static_cast(min_points_and_distance_ratio_ / distance + 0.5f), min_points_), + std::max( + static_cast(std::lround(min_points_and_distance_ratio_ / distance)), min_points_), max_points_); const int points_num = kd_tree_->radiusSearch(i, search_radius_, k_indices, k_distances, min_points_threshold); @@ -200,7 +202,8 @@ void RadiusSearch2dFilter::filter( const float distance = std::hypot(xy_cloud->points[i].x - pose.position.x, xy_cloud->points[i].y - pose.position.y); const int min_points_threshold = std::min( - std::max(static_cast(min_points_and_distance_ratio_ / distance + 0.5f), min_points_), + std::max( + static_cast(std::lround(min_points_and_distance_ratio_ / distance)), min_points_), max_points_); const int points_num = kd_tree_->radiusSearch(i, search_radius_, k_indices, k_distances, min_points_threshold); From 50ba24a758e92b10d4d21bc21d792bc4136d49ba Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 13:51:01 +0900 Subject: [PATCH 059/273] fix(autoware_costmap_generator): fix clang-diagnostic-unused-private-field (#9395) fix: clang-diagnostic-unused-private-field Signed-off-by: kobayu858 --- .../autoware/costmap_generator/utils/points_to_costmap.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/planning/autoware_costmap_generator/include/autoware/costmap_generator/utils/points_to_costmap.hpp b/planning/autoware_costmap_generator/include/autoware/costmap_generator/utils/points_to_costmap.hpp index cda96ea9b3283..1cf3365b0f344 100644 --- a/planning/autoware_costmap_generator/include/autoware/costmap_generator/utils/points_to_costmap.hpp +++ b/planning/autoware_costmap_generator/include/autoware/costmap_generator/utils/points_to_costmap.hpp @@ -79,8 +79,6 @@ class PointsToCostmap double grid_resolution_; double grid_position_x_; double grid_position_y_; - double y_cell_size_; - double x_cell_size_; /// \brief initialize gridmap parameters /// \param[in] gridmap: gridmap object to be initialized From eafa68e47fb5cb08c16ebf28b28cf342a315c257 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 14:35:52 +0900 Subject: [PATCH 060/273] fix(autoware_obstacle_cruise_planner): fix clang-diagnostic-defaulted-function-deleted (#9398) fix: clang-diagnostic-defaulted-function-deleted Signed-off-by: kobayu858 --- .../autoware/obstacle_cruise_planner/planner_interface.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp index a2265ea6affa0..df46f32610150 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp @@ -66,8 +66,6 @@ class PlannerInterface node.declare_parameter("slow_down.moving_object_hysteresis_range"); } - PlannerInterface() = default; - void setParam( const bool enable_debug_info, const bool enable_calculation_time_info, const bool use_pointcloud, const double min_behavior_stop_margin, From f58d71dc9edd847de8a1ae10f421dc4c23b9ad78 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 14:59:48 +0900 Subject: [PATCH 061/273] fix(autoware_freespace_planning_algorithms): fix clang-diagnostic-unused-private-field (#9396) * fix: clang-diagnostic-unused-private-field Signed-off-by: kobayu858 * fix: build error Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../include/autoware/freespace_planning_algorithms/rrtstar.hpp | 2 -- .../autoware_freespace_planning_algorithms/src/rrtstar.cpp | 3 +-- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/rrtstar.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/rrtstar.hpp index b30692ce8da2d..1bdc7105067d4 100644 --- a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/rrtstar.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/rrtstar.hpp @@ -68,8 +68,6 @@ class RRTStar : public AbstractPlanningAlgorithm // algorithm specific param const RRTStarParam rrtstar_param_; - - const VehicleShape original_vehicle_shape_; }; } // namespace autoware::freespace_planning_algorithms diff --git a/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp b/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp index b9343f680fa1a..696d04a06cb28 100644 --- a/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp @@ -33,8 +33,7 @@ RRTStar::RRTStar( original_vehicle_shape.width + 2 * rrtstar_param.margin, original_vehicle_shape.base_length, original_vehicle_shape.max_steering, original_vehicle_shape.base2back + rrtstar_param.margin)), - rrtstar_param_(rrtstar_param), - original_vehicle_shape_(original_vehicle_shape) + rrtstar_param_(rrtstar_param) { if (rrtstar_param_.margin <= 0) { throw std::invalid_argument("rrt's collision margin must be greater than 0"); From 41cec8711513bb38b8d27242c920554e3dc1f4ae Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 16:07:53 +0900 Subject: [PATCH 062/273] fix(autoware_surround_obstacle_checker): fix clang-diagnostic-unused-private-field (#9399) * fix: clang-diagnostic-unused-private-field Signed-off-by: kobayu858 * refactor: fmt Signed-off-by: kobayu858 * refactor: fmt Signed-off-by: kobayu858 * refactor: fmt Signed-off-by: kobayu858 * fix: hpp Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/debug_marker.cpp | 11 +++++------ .../src/debug_marker.hpp | 3 +-- .../autoware_surround_obstacle_checker/src/node.cpp | 6 +++--- 3 files changed, 9 insertions(+), 11 deletions(-) diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp index 92429504c7d5e..57d9cc8bc67a7 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp @@ -60,13 +60,12 @@ using autoware::universe_utils::createMarkerScale; using autoware::universe_utils::createPoint; SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double base_link2front, - const std::string & object_label, const double & surround_check_front_distance, - const double & surround_check_side_distance, const double & surround_check_back_distance, - const double & surround_check_hysteresis_distance, const geometry_msgs::msg::Pose & self_pose, - const rclcpp::Clock::SharedPtr clock, rclcpp::Node & node) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const std::string & object_label, + const double & surround_check_front_distance, const double & surround_check_side_distance, + const double & surround_check_back_distance, const double & surround_check_hysteresis_distance, + const geometry_msgs::msg::Pose & self_pose, const rclcpp::Clock::SharedPtr clock, + rclcpp::Node & node) : vehicle_info_(vehicle_info), - base_link2front_(base_link2front), object_label_(object_label), surround_check_front_distance_(surround_check_front_distance), surround_check_side_distance_(surround_check_side_distance), diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp index ba8877b539e81..17ec2631b2dad 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp @@ -56,7 +56,7 @@ class SurroundObstacleCheckerDebugNode { public: explicit SurroundObstacleCheckerDebugNode( - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double base_link2front, + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const std::string & object_label, const double & surround_check_front_distance, const double & surround_check_side_distance, const double & surround_check_back_distance, const double & surround_check_hysteresis_distance, const geometry_msgs::msg::Pose & self_pose, @@ -77,7 +77,6 @@ class SurroundObstacleCheckerDebugNode rclcpp::Publisher::SharedPtr vehicle_footprint_recover_offset_pub_; autoware::vehicle_info_utils::VehicleInfo vehicle_info_; - double base_link2front_; std::string object_label_; double surround_check_front_distance_; double surround_check_side_distance_; diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index da0dd0ec09a26..70e81fa3b1d12 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -126,9 +126,9 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio const auto param = param_listener_->get_params(); const auto check_distances = getCheckDistances(param.debug_footprint_label); debug_ptr_ = std::make_shared( - vehicle_info_, vehicle_info_.max_longitudinal_offset_m, param.debug_footprint_label, - check_distances.at(0), check_distances.at(1), check_distances.at(2), - param.surround_check_hysteresis_distance, odometry_ptr_->pose.pose, this->get_clock(), *this); + vehicle_info_, param.debug_footprint_label, check_distances.at(0), check_distances.at(1), + check_distances.at(2), param.surround_check_hysteresis_distance, odometry_ptr_->pose.pose, + this->get_clock(), *this); } } From 5fbb9d2c7fe16b22c4ad02de3b2ea557bd19cd7d Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 20 Nov 2024 17:31:47 +0900 Subject: [PATCH 063/273] feat(goal_planner): remove unnecessary member from ThreadSafeData (#9393) Signed-off-by: Mamoru Sobue --- .../goal_planner_module.hpp | 7 ++- .../thread_data.hpp | 13 ----- .../src/goal_planner_module.cpp | 58 ++++++++++++------- 3 files changed, 42 insertions(+), 36 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 2edd0714eceff..5d7fe103a9346 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -73,6 +73,7 @@ struct GoalPlannerDebugData std::vector ego_polygons_expanded{}; lanelet::ConstLanelet expanded_pull_over_lane_between_ego{}; Polygon2d objects_extraction_polygon{}; + utils::path_safety_checker::CollisionCheckDebugMap collision_check{}; }; struct LastApprovalData @@ -326,7 +327,6 @@ class GoalPlannerModule : public SceneModuleInterface autoware::universe_utils::LinearRing2d vehicle_footprint_; std::recursive_mutex mutex_; - // TODO(Mamoru Sobue): isSafePath() modifies ThreadSafeData::check_collision, avoid this mutable mutable ThreadSafeData thread_safe_data_; // TODO(soblin): organize part of thread_safe_data and previous data to PullOverContextData @@ -414,7 +414,8 @@ class GoalPlannerModule : public SceneModuleInterface bool planFreespacePath( std::shared_ptr planner_data, const std::shared_ptr goal_searcher, const GoalCandidates & goal_candidates, - const std::shared_ptr occupancy_grid_map); + const std::shared_ptr occupancy_grid_map, + const PredictedObjects & static_target_objects); bool canReturnToLaneParking(const PullOverContextData & context_data); // plan pull over path @@ -477,7 +478,7 @@ class GoalPlannerModule : public SceneModuleInterface * @brief Checks if the current path is safe. * @return If the path is safe in the current state, true. */ - bool isSafePath( + std::pair isSafePath( const std::shared_ptr planner_data, const bool found_pull_over_path, const std::optional & pull_over_path_opt, const PathDecisionState & prev_data, const GoalPlannerParameters & parameters, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp index 9df48fb5f0a5f..549319b42ee4c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/thread_data.hpp @@ -111,10 +111,6 @@ class ThreadSafeData prev_data_ = PathDecisionState{}; } - // main --> lane/freespace - DEFINE_SETTER_GETTER_WITH_MUTEX(PredictedObjects, static_target_objects) - DEFINE_SETTER_GETTER_WITH_MUTEX(PredictedObjects, dynamic_target_objects) - // main --> lane DEFINE_SETTER_GETTER_WITH_MUTEX(PathDecisionState, prev_data) @@ -125,8 +121,6 @@ class ThreadSafeData // main <--> lane/freespace DEFINE_GETTER_WITH_MUTEX(std::shared_ptr, pull_over_path) DEFINE_GETTER_WITH_MUTEX(std::optional, last_path_update_time) - DEFINE_SETTER_GETTER_WITH_MUTEX( - utils::path_safety_checker::CollisionCheckDebugMap, collision_check) private: void set_pull_over_path_no_lock(const PullOverPath & path) @@ -145,18 +139,11 @@ class ThreadSafeData void set_no_lock(const std::vector & arg) { pull_over_path_candidates_ = arg; } void set_no_lock(const std::shared_ptr & arg) { set_pull_over_path_no_lock(arg); } void set_no_lock(const PullOverPath & arg) { set_pull_over_path_no_lock(arg); } - void set_no_lock(const utils::path_safety_checker::CollisionCheckDebugMap & arg) - { - collision_check_ = arg; - } std::shared_ptr pull_over_path_{nullptr}; std::vector pull_over_path_candidates_; std::optional last_path_update_time_; std::optional closest_start_pose_{}; - utils::path_safety_checker::CollisionCheckDebugMap collision_check_{}; - PredictedObjects static_target_objects_{}; - PredictedObjects dynamic_target_objects_{}; PathDecisionState prev_data_{}; std::recursive_mutex & mutex_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index f8a35134e0407..b4fa4dfe30d7a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -395,8 +395,8 @@ void GoalPlannerModule::onFreespaceParkingTimer() } // end of critical section if ( - !local_planner_data || !current_status_opt || !parameters_opt || !vehicle_footprint_opt || - !goal_candidates_opt) { + !local_planner_data || !current_status_opt || !occupancy_grid_map || !parameters_opt || + !vehicle_footprint_opt || !goal_candidates_opt) { RCLCPP_ERROR( getLogger(), "failed to get valid planner_data/current_status/parameters in " @@ -434,20 +434,43 @@ void GoalPlannerModule::onFreespaceParkingTimer() return; } + const double vehicle_width = planner_data_->parameters.vehicle_width; + const bool left_side_parking = parameters.parking_policy == ParkingPolicy::LEFT_SIDE; + const auto pull_over_lanes = goal_planner_utils::getPullOverLanes( + *(local_planner_data->route_handler), left_side_parking, parameters.backward_goal_search_length, + parameters.forward_goal_search_length); + const auto objects_extraction_polygon = goal_planner_utils::generateObjectExtractionPolygon( + pull_over_lanes, left_side_parking, parameters.detection_bound_offset, + parameters.margin_from_boundary + parameters.max_lateral_offset + vehicle_width); + + PredictedObjects dynamic_target_objects{}; + for (const auto & object : local_planner_data->dynamic_object->objects) { + const auto object_polygon = universe_utils::toPolygon2d(object); + if ( + objects_extraction_polygon.has_value() && + boost::geometry::intersects(object_polygon, objects_extraction_polygon.value())) { + dynamic_target_objects.objects.push_back(object); + } + } + const auto static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( + dynamic_target_objects, parameters.th_moving_object_velocity); + const bool is_new_costmap = (clock_->now() - local_planner_data->costmap->header.stamp).seconds() < 1.0; constexpr double path_update_duration = 1.0; if ( isStuck( - thread_safe_data_.get_static_target_objects(), thread_safe_data_.get_dynamic_target_objects(), - local_planner_data, occupancy_grid_map, parameters) && + static_target_objects, dynamic_target_objects, local_planner_data, occupancy_grid_map, + parameters) && is_new_costmap && needPathUpdate( local_planner_data->self_odometry->pose.pose, path_update_duration, modified_goal_opt, parameters)) { auto goal_searcher = std::make_shared(parameters, vehicle_footprint); - planFreespacePath(local_planner_data, goal_searcher, goal_candidates, occupancy_grid_map); + planFreespacePath( + local_planner_data, goal_searcher, goal_candidates, occupancy_grid_map, + static_target_objects); } } @@ -504,10 +527,6 @@ void GoalPlannerModule::updateData() const auto static_target_objects = utils::path_safety_checker::filterObjectsByVelocity( dynamic_target_objects, p->th_moving_object_velocity); - // these objects are used for path collision check not for safety check - thread_safe_data_.set_static_target_objects(static_target_objects); - thread_safe_data_.set_dynamic_target_objects(dynamic_target_objects); - // update goal searcher and generate goal candidates if (goal_candidates_.empty()) { goal_candidates_ = generateGoalCandidates(); @@ -583,9 +602,10 @@ void GoalPlannerModule::updateData() // save "old" state const auto prev_decision_state = path_decision_controller_.get_current_state(); - const bool is_current_safe = isSafePath( + const auto [is_current_safe, collision_check_map] = isSafePath( planner_data_, found_pull_over_path, pull_over_path_recv, prev_decision_state, *parameters_, ego_predicted_path_params_, objects_filtering_params_, safety_check_params_); + debug_data_.collision_check = collision_check_map; // update to latest state path_decision_controller_.transit_state( found_pull_over_path, clock_->now(), static_target_objects, dynamic_target_objects, @@ -768,12 +788,11 @@ double GoalPlannerModule::calcModuleRequestLength() const bool GoalPlannerModule::planFreespacePath( std::shared_ptr planner_data, const std::shared_ptr goal_searcher, const GoalCandidates & goal_candidates_arg, - const std::shared_ptr occupancy_grid_map) + const std::shared_ptr occupancy_grid_map, + const PredictedObjects & static_target_objects) { auto goal_candidates = goal_candidates_arg; - goal_searcher->update( - goal_candidates, occupancy_grid_map, planner_data, - thread_safe_data_.get_static_target_objects()); + goal_searcher->update(goal_candidates, occupancy_grid_map, planner_data, static_target_objects); debug_data_.freespace_planner.num_goal_candidates = goal_candidates.size(); debug_data_.freespace_planner.is_planning = true; @@ -2201,7 +2220,7 @@ static std::vector filterOb return refined_filtered_objects; } -bool GoalPlannerModule::isSafePath( +std::pair GoalPlannerModule::isSafePath( const std::shared_ptr planner_data, const bool found_pull_over_path, const std::optional & pull_over_path_opt, const PathDecisionState & prev_data, const GoalPlannerParameters & parameters, @@ -2212,9 +2231,10 @@ bool GoalPlannerModule::isSafePath( using autoware::behavior_path_planner::utils::path_safety_checker::createPredictedPath; using autoware::behavior_path_planner::utils::path_safety_checker:: filterPredictedPathAfterTargetPose; + CollisionCheckDebugMap collision_check{}; if (!found_pull_over_path || !pull_over_path_opt) { - return false; + return {false, collision_check}; } const auto & pull_over_path = pull_over_path_opt.value(); const auto & current_pull_over_path = pull_over_path.getCurrentPath(); @@ -2299,7 +2319,6 @@ bool GoalPlannerModule::isSafePath( const double hysteresis_factor = prev_data.is_stable_safe ? 1.0 : parameters.hysteresis_factor_expand_rate; - CollisionCheckDebugMap collision_check{}; const bool current_is_safe = std::invoke([&]() { if (parameters.safety_check_params.method == "RSS") { return autoware::behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS( @@ -2319,7 +2338,6 @@ bool GoalPlannerModule::isSafePath( parameters.safety_check_params.method.c_str()); throw std::domain_error("[pull_over] invalid safety check method"); }); - thread_safe_data_.set_collision_check(collision_check); /* * ==== is_safe @@ -2334,7 +2352,7 @@ bool GoalPlannerModule::isSafePath( * | | | | | | | | * 0 =========================-------==========-- t */ - return current_is_safe; + return {current_is_safe, collision_check}; } void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) @@ -2451,7 +2469,6 @@ void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) } } - auto collision_check = thread_safe_data_.get_collision_check(); // safety check if (parameters_->safety_check_params.enable_safety_check) { if (goal_planner_data_.ego_predicted_path.size() > 0) { @@ -2465,6 +2482,7 @@ void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) goal_planner_data_.filtered_objects, "filtered_objects", 0, 0.0, 0.5, 0.9)); } + auto collision_check = debug_data_.collision_check; if (parameters_->safety_check_params.method == "RSS") { add(showSafetyCheckInfo(collision_check, "object_debug_info")); } From 67bc182330948cadb6b5231d614ced4529857d48 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 18:05:03 +0900 Subject: [PATCH 064/273] fix(autoware_behavior_velocity_intersection_module): fix clang-diagnostic-unused-lambda-capture (#9407) fix: clang-diagnostic-unused-parameter Signed-off-by: kobayu858 --- .../src/manager.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp index dcb0ebb5ba688..39ed8e80412a6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/manager.cpp @@ -360,7 +360,7 @@ IntersectionModuleManager::getModuleExpiredFunction( const auto lane_set = planning_utils::getLaneletsOnPath( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); - return [this, lane_set](const std::shared_ptr & scene_module) { + return [lane_set](const std::shared_ptr & scene_module) { const auto intersection_module = std::dynamic_pointer_cast(scene_module); const auto & associative_ids = intersection_module->getAssociativeIds(); for (const auto & lane : lane_set) { @@ -555,7 +555,7 @@ MergeFromPrivateModuleManager::getModuleExpiredFunction( const auto lane_set = planning_utils::getLaneletsOnPath( path, planner_data_->route_handler_->getLaneletMapPtr(), planner_data_->current_odometry->pose); - return [this, lane_set](const std::shared_ptr & scene_module) { + return [lane_set](const std::shared_ptr & scene_module) { const auto merge_from_private_module = std::dynamic_pointer_cast(scene_module); const auto & associative_ids = merge_from_private_module->getAssociativeIds(); From ec22883354038d5c0db2c93e96e8222f6d68401e Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 20 Nov 2024 18:05:19 +0900 Subject: [PATCH 065/273] test(autoware_test_utils): add TrafficLight to map, fix launcher (#9318) Signed-off-by: Mamoru Sobue --- .../launch/psim_intersection.launch.xml | 2 +- .../launch/psim_road_shoulder.launch.xml | 2 +- .../rviz/psim_test_map.rviz | 10 +- .../test_map/intersection/lanelet2_map.osm | 733 ++++++++++++++++++ 4 files changed, 742 insertions(+), 5 deletions(-) diff --git a/common/autoware_test_utils/launch/psim_intersection.launch.xml b/common/autoware_test_utils/launch/psim_intersection.launch.xml index 70ae619e67705..723dd7352219d 100644 --- a/common/autoware_test_utils/launch/psim_intersection.launch.xml +++ b/common/autoware_test_utils/launch/psim_intersection.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml b/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml index 0d61abef95d2c..7dd888a036f9d 100644 --- a/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml +++ b/common/autoware_test_utils/launch/psim_road_shoulder.launch.xml @@ -2,7 +2,7 @@ - + diff --git a/common/autoware_test_utils/rviz/psim_test_map.rviz b/common/autoware_test_utils/rviz/psim_test_map.rviz index 022621885ed72..8475c94b86bb4 100644 --- a/common/autoware_test_utils/rviz/psim_test_map.rviz +++ b/common/autoware_test_utils/rviz/psim_test_map.rviz @@ -24,6 +24,8 @@ Panels: Name: AutowareStatePanel - Class: rviz_plugins::SimulatedClockPanel Name: SimulatedClockPanel + - Class: rviz_plugins::TrafficLightPublishPanel + Name: TrafficLightPublishPanel Visualization Manager: Class: "" Displays: @@ -4429,7 +4431,7 @@ Visualization Manager: Value: /rviz/routing/rough_goal - Acceleration: 0 Class: rviz_plugins/PedestrianInitialPoseTool - Interactive: true + Interactive: false Max velocity: 33.29999923706055 Min velocity: -33.29999923706055 Pose Topic: /simulation/dummy_perception_publisher/object_info @@ -4443,7 +4445,7 @@ Visualization Manager: - Acceleration: 0 Class: rviz_plugins/CarInitialPoseTool H vehicle height: 2 - Interactive: true + Interactive: false L vehicle length: 4 Max velocity: 33.29999923706055 Min velocity: -33.29999923706055 @@ -4459,7 +4461,7 @@ Visualization Manager: - Acceleration: 0 Class: rviz_plugins/BusInitialPoseTool H vehicle height: 3.5 - Interactive: true + Interactive: false L vehicle length: 10.5 Max velocity: 33.29999923706055 Min velocity: -33.29999923706055 @@ -4558,6 +4560,8 @@ Window Geometry: collapsed: false Tool Properties: collapsed: false + TrafficLightPublishPanel: + collapsed: false Views: collapsed: false Width: 1920 diff --git a/common/autoware_test_utils/test_map/intersection/lanelet2_map.osm b/common/autoware_test_utils/test_map/intersection/lanelet2_map.osm index 92307e28cf6cc..c5c5b7b1fc657 100644 --- a/common/autoware_test_utils/test_map/intersection/lanelet2_map.osm +++ b/common/autoware_test_utils/test_map/intersection/lanelet2_map.osm @@ -15199,6 +15199,393 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -20570,6 +20957,180 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -20997,6 +21558,7 @@ + @@ -21009,6 +21571,7 @@ + @@ -21021,6 +21584,7 @@ + @@ -21034,6 +21598,7 @@ + @@ -21046,6 +21611,7 @@ + @@ -21060,6 +21626,7 @@ + @@ -21072,6 +21639,7 @@ + @@ -21084,6 +21652,7 @@ + @@ -21097,6 +21666,7 @@ + @@ -21109,6 +21679,7 @@ + @@ -21122,6 +21693,7 @@ + @@ -21134,6 +21706,7 @@ + @@ -21148,6 +21721,7 @@ + @@ -21161,6 +21735,7 @@ + @@ -21174,6 +21749,7 @@ + @@ -21187,6 +21763,7 @@ + @@ -21200,6 +21777,7 @@ + @@ -21213,6 +21791,7 @@ + @@ -21226,6 +21805,7 @@ + @@ -21240,6 +21820,7 @@ + @@ -21254,6 +21835,7 @@ + @@ -21267,6 +21849,7 @@ + @@ -21280,6 +21863,7 @@ + @@ -21293,6 +21877,7 @@ + @@ -21306,6 +21891,7 @@ + @@ -21350,6 +21936,7 @@ + @@ -21364,6 +21951,7 @@ + @@ -21376,6 +21964,7 @@ + @@ -21671,6 +22260,7 @@ + @@ -22374,4 +22964,147 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 228400c75e7f748b5a32c3984b30732c2bfb091b Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 18:09:42 +0900 Subject: [PATCH 066/273] fix(autoware_behavior_velocity_intersection_module): fix clang-diagnostic-unused-parameter (#9409) fix: clang-diagnostic-unused-parameter Signed-off-by: kobayu858 --- .../src/scene_intersection.cpp | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 844380f135559..8115f52437a04 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -490,8 +490,10 @@ VisitorSwitch(Ts...) -> VisitorSwitch; template void prepareRTCByDecisionResult( - const T & result, const tier4_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, - double * default_distance, bool * occlusion_safety, double * occlusion_distance) + [[maybe_unused]] const T & result, + [[maybe_unused]] const tier4_planning_msgs::msg::PathWithLaneId & path, + [[maybe_unused]] bool * default_safety, [[maybe_unused]] double * default_distance, + [[maybe_unused]] bool * occlusion_safety, [[maybe_unused]] double * occlusion_distance) { static_assert("Unsupported type passed to prepareRTCByDecisionResult"); return; @@ -704,10 +706,14 @@ void IntersectionModule::prepareRTCStatus( template void reactRTCApprovalByDecisionResult( - const bool rtc_default_approved, const bool rtc_occlusion_approved, const T & decision_result, - const IntersectionModule::PlannerParam & planner_param, const double baselink2front, - tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + [[maybe_unused]] const bool rtc_default_approved, + [[maybe_unused]] const bool rtc_occlusion_approved, [[maybe_unused]] const T & decision_result, + [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, + [[maybe_unused]] const double baselink2front, + [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, + [[maybe_unused]] StopReason * stop_reason, + [[maybe_unused]] VelocityFactorInterface * velocity_factor, + [[maybe_unused]] IntersectionModule::DebugData * debug_data) { static_assert("Unsupported type passed to reactRTCByDecisionResult"); return; From a4a5749314de3474fe6103a6c27f9027cbe4e16c Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 20 Nov 2024 18:52:47 +0900 Subject: [PATCH 067/273] feat(behavior_path_planner_common): use azimuth for interpolatePose (#9362) Signed-off-by: kosuke55 --- .../src/utils/path_utils.cpp | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp index d6f56f9c90168..1e2ad668bf28f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp @@ -329,6 +329,8 @@ std::vector spline_two_points( std::vector interpolatePose( const Pose & start_pose, const Pose & end_pose, const double resample_interval) { + using autoware::universe_utils::calcAzimuthAngle; + std::vector interpolated_poses{}; // output const double distance = @@ -351,14 +353,21 @@ std::vector interpolatePose( std::sin(tf2::getYaw(end_pose.orientation)), new_s); for (size_t i = 0; i < interpolated_x.size(); ++i) { Pose pose{}; - pose = autoware::universe_utils::calcInterpolatedPose( - end_pose, start_pose, (distance - new_s.at(i)) / distance); pose.position.x = interpolated_x.at(i); pose.position.y = interpolated_y.at(i); pose.position.z = end_pose.position.z; interpolated_poses.push_back(pose); } + // insert orientation + for (size_t i = 0; i < interpolated_poses.size(); ++i) { + const double yaw = calcAzimuthAngle( + interpolated_poses.at(i).position, i < interpolated_poses.size() - 1 + ? interpolated_poses.at(i + 1).position + : end_pose.position); + interpolated_poses.at(i).orientation = autoware::universe_utils::createQuaternionFromYaw(yaw); + } + return interpolated_poses; } From 2ac579f647b53042e6a2a5b82f81d06c3b3140ed Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 20 Nov 2024 18:53:09 +0900 Subject: [PATCH 068/273] fix(behavior_path_planner_common): prevent duplicated point insertion in cutOverlappedLanes (#9363) Signed-off-by: kosuke55 --- .../utils/drivable_area_expansion/static_drivable_area.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 012c42a379c00..1c6295f3e70ef 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -729,10 +729,13 @@ std::vector cutOverlappedLanes( } // Step2. pick up only path points within drivable lanes + std::set path_point_indices; for (const auto & drivable_lanes : shorten_lanes) { for (size_t i = start_point_idx; i < original_points.size(); ++i) { - if (is_point_in_drivable_lanes(drivable_lanes, original_points.at(i))) { - path.points.push_back(original_points.at(i)); + const auto & p = original_points.at(i); + if (is_point_in_drivable_lanes(drivable_lanes, p) && path_point_indices.count(i) == 0) { + path.points.push_back(p); + path_point_indices.insert(i); continue; } start_point_idx = i; From dea1778f1b42bb440d9d1c07c52c2306653d14ab Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 20 Nov 2024 19:03:14 +0900 Subject: [PATCH 069/273] feat(autoware_test_utils): add parser for LaneletRoute, TrackedObject (#9317) Signed-off-by: Mamoru Sobue --- .../config/sample_topic_snapshot.yaml | 3 + .../autoware_test_utils/mock_data_parser.hpp | 16 ++ .../src/mock_data_parser.cpp | 49 +++++ .../src/topic_snapshot_saver.cpp | 21 +- .../test/test_mock_data_parser.cpp | 207 ++++++++++++++++++ 5 files changed, 289 insertions(+), 7 deletions(-) diff --git a/common/autoware_test_utils/config/sample_topic_snapshot.yaml b/common/autoware_test_utils/config/sample_topic_snapshot.yaml index 8f6e0d4ca2627..d9eff5d579540 100644 --- a/common/autoware_test_utils/config/sample_topic_snapshot.yaml +++ b/common/autoware_test_utils/config/sample_topic_snapshot.yaml @@ -24,3 +24,6 @@ fields: - name: dynamic_object type: PredictedObjects # autoware_perception_msgs::msg::PredictedObjects topic: /perception/object_recognition/objects +# - name: tracked_object +# type: TrackedObjects # autoware_perception_msgs::msg::TrackedObjects +# topic: /perception/object_recognition/tracking/objects diff --git a/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp index adce8176a2ade..5d36e8aefef3b 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp @@ -20,6 +20,7 @@ #include #include +#include #include #include #include @@ -47,6 +48,9 @@ using autoware_perception_msgs::msg::PredictedObjectKinematics; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; using autoware_perception_msgs::msg::Shape; +using autoware_perception_msgs::msg::TrackedObject; +using autoware_perception_msgs::msg::TrackedObjectKinematics; +using autoware_perception_msgs::msg::TrackedObjects; using autoware_perception_msgs::msg::TrafficLightElement; using autoware_perception_msgs::msg::TrafficLightGroup; using autoware_perception_msgs::msg::TrafficLightGroupArray; @@ -131,6 +135,9 @@ std::vector parse(const YAML::Node & node); template <> std::vector parse(const YAML::Node & node); +template <> +LaneletRoute parse(const YAML::Node & node); + template <> std::vector parse(const YAML::Node & node); @@ -155,6 +162,15 @@ PredictedObject parse(const YAML::Node & node); template <> PredictedObjects parse(const YAML::Node & node); +template <> +TrackedObjectKinematics parse(const YAML::Node & node); + +template <> +TrackedObject parse(const YAML::Node & node); + +template <> +TrackedObjects parse(const YAML::Node & node); + template <> TrafficLightGroupArray parse(const YAML::Node & node); diff --git a/common/autoware_test_utils/src/mock_data_parser.cpp b/common/autoware_test_utils/src/mock_data_parser.cpp index d2c6de5c0a46f..9e895c7b4027d 100644 --- a/common/autoware_test_utils/src/mock_data_parser.cpp +++ b/common/autoware_test_utils/src/mock_data_parser.cpp @@ -204,6 +204,17 @@ std::vector parse(const YAML::Node & node) return segments; } +template <> +LaneletRoute parse(const YAML::Node & node) +{ + LaneletRoute route; + + route.start_pose = parse(node["start_pose"]); + route.goal_pose = parse(node["goal_pose"]); + route.segments = parse>(node["segments"]); + return route; +} + template <> std::vector parse>(const YAML::Node & node) { @@ -330,6 +341,44 @@ PredictedObjects parse(const YAML::Node & node) return msg; } +template <> +TrackedObjectKinematics parse(const YAML::Node & node) +{ + TrackedObjectKinematics msg; + msg.pose_with_covariance = parse(node["pose_with_covariance"]); + msg.twist_with_covariance = parse(node["twist_with_covariance"]); + msg.acceleration_with_covariance = + parse(node["acceleration_with_covariance"]); + msg.orientation_availability = node["orientation_availability"].as(); + msg.is_stationary = node["is_stationary"].as(); + return msg; +} + +template <> +TrackedObject parse(const YAML::Node & node) +{ + TrackedObject msg; + msg.object_id = parse(node["object_id"]); + msg.existence_probability = node["existence_probability"].as(); + for (const auto & classification_node : node["classification"]) { + msg.classification.push_back(parse(classification_node)); + } + msg.kinematics = parse(node["kinematics"]); + msg.shape = parse(node["shape"]); + return msg; +} + +template <> +TrackedObjects parse(const YAML::Node & node) +{ + TrackedObjects msg; + msg.header = parse
(node["header"]); + for (const auto & object_node : node["objects"]) { + msg.objects.push_back(parse(object_node)); + } + return msg; +} + template <> TrafficLightElement parse(const YAML::Node & node) { diff --git a/common/autoware_test_utils/src/topic_snapshot_saver.cpp b/common/autoware_test_utils/src/topic_snapshot_saver.cpp index 29b1e19f272c2..82700be9e3f54 100644 --- a/common/autoware_test_utils/src/topic_snapshot_saver.cpp +++ b/common/autoware_test_utils/src/topic_snapshot_saver.cpp @@ -19,6 +19,7 @@ #include #include +#include #include #include #include @@ -34,12 +35,13 @@ #include using MessageType = std::variant< - nav_msgs::msg::Odometry, // 0 - geometry_msgs::msg::AccelWithCovarianceStamped, // 1 - autoware_perception_msgs::msg::PredictedObjects, // 2 - autoware_adapi_v1_msgs::msg::OperationModeState, // 3 - autoware_planning_msgs::msg::LaneletRoute, // 4 - autoware_perception_msgs::msg::TrafficLightGroupArray // 5 + nav_msgs::msg::Odometry, // 0 + geometry_msgs::msg::AccelWithCovarianceStamped, // 1 + autoware_perception_msgs::msg::PredictedObjects, // 2 + autoware_adapi_v1_msgs::msg::OperationModeState, // 3 + autoware_planning_msgs::msg::LaneletRoute, // 4 + autoware_perception_msgs::msg::TrafficLightGroupArray, // 5 + autoware_perception_msgs::msg::TrackedObjects // 6 >; std::optional get_topic_index(const std::string & name) @@ -62,6 +64,9 @@ std::optional get_topic_index(const std::string & name) if (name == "TrafficLightGroupArray") { return 5; } + if (name == "TrackedObjects") { + return 6; + } return std::nullopt; } @@ -185,6 +190,7 @@ class TopicSnapShotSaver REGISTER_CALLBACK(3); REGISTER_CALLBACK(4); REGISTER_CALLBACK(5); + REGISTER_CALLBACK(6); } } @@ -231,6 +237,7 @@ class TopicSnapShotSaver REGISTER_WRITE_TYPE(3); REGISTER_WRITE_TYPE(4); REGISTER_WRITE_TYPE(5); + REGISTER_WRITE_TYPE(6); } const std::string desc = std::string(R"(# @@ -241,7 +248,7 @@ class TopicSnapShotSaver # map_path_uri: package:/// # fields(this is array) # - name: -# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TBD} +# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | TBD} # topic: # )"); diff --git a/common/autoware_test_utils/test/test_mock_data_parser.cpp b/common/autoware_test_utils/test/test_mock_data_parser.cpp index 0aeb5fb1db462..a0dd0fce9bd29 100644 --- a/common/autoware_test_utils/test/test_mock_data_parser.cpp +++ b/common/autoware_test_utils/test/test_mock_data_parser.cpp @@ -459,6 +459,188 @@ const char g_complete_yaml[] = R"( is_autonomous_mode_available: true is_local_mode_available: true is_remote_mode_available: true +tracked_object: + header: + stamp: + sec: 288 + nanosec: 743249865 + frame_id: map + objects: + - object_id: + uuid: + - 35 + - 106 + - 130 + - 18 + - 249 + - 15 + - 247 + - 148 + - 31 + - 235 + - 198 + - 121 + - 150 + - 136 + - 225 + - 99 + existence_probability: 0.00000 + classification: + - label: 1 + probability: 1.00000 + kinematics: + pose_with_covariance: + pose: + position: + x: 269.944 + y: 376.116 + z: 101.346 + orientation: + x: 0.00000 + y: 0.00000 + z: -0.715560 + w: 0.698551 + covariance: + - 0.0267953 + - 0.00119480 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00119480 + - 0.0831472 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00551386 + twist_with_covariance: + twist: + linear: + x: 2.99743 + y: -0.0100529 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: -0.00913898 + covariance: + - 0.609089 + - -0.00201817 + - 0.00000 + - 0.00000 + - 0.00000 + - -0.00183470 + - -0.00201817 + - 0.000777658 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000706962 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.0100000 + - 0.00000 + - -0.00183470 + - 0.000706962 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000642693 + acceleration_with_covariance: + accel: + linear: + x: 0.00000 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + orientation_availability: 1 + is_stationary: false + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 4.40000 + y: 1.73071 + z: 1.00000 )"; TEST(ParseFunctions, CompleteYAMLTest) @@ -572,6 +754,31 @@ TEST(ParseFunctions, CompleteYAMLTest) EXPECT_EQ(operation_mode.is_autonomous_mode_available, true); EXPECT_EQ(operation_mode.is_local_mode_available, true); EXPECT_EQ(operation_mode.is_remote_mode_available, true); + + const auto tracked_objects = parse(config["tracked_object"]); + EXPECT_EQ(tracked_objects.header.stamp.sec, 288); + EXPECT_EQ(tracked_objects.header.stamp.nanosec, 743249865); + EXPECT_EQ(tracked_objects.header.frame_id, "map"); + EXPECT_EQ(tracked_objects.objects.at(0).object_id.uuid.at(0), 35); + EXPECT_FLOAT_EQ(tracked_objects.objects.at(0).existence_probability, 0.0); + EXPECT_EQ(tracked_objects.objects.at(0).classification.at(0).label, 1); + EXPECT_FLOAT_EQ(tracked_objects.objects.at(0).classification.at(0).probability, 1.0); + EXPECT_FLOAT_EQ( + tracked_objects.objects.at(0).kinematics.pose_with_covariance.pose.position.x, 269.944); + EXPECT_FLOAT_EQ( + tracked_objects.objects.at(0).kinematics.pose_with_covariance.covariance.at(0), 0.0267953); + EXPECT_FLOAT_EQ( + tracked_objects.objects.at(0).kinematics.twist_with_covariance.twist.linear.x, 2.99743); + EXPECT_FLOAT_EQ( + tracked_objects.objects.at(0).kinematics.twist_with_covariance.twist.angular.z, -0.00913898); + EXPECT_FLOAT_EQ( + tracked_objects.objects.at(0).kinematics.twist_with_covariance.covariance.at(0), 0.609089); + EXPECT_EQ(tracked_objects.objects.at(0).kinematics.orientation_availability, 1); + EXPECT_EQ(tracked_objects.objects.at(0).kinematics.is_stationary, false); + EXPECT_EQ(tracked_objects.objects.at(0).shape.type, 0); + EXPECT_EQ(tracked_objects.objects.at(0).shape.dimensions.x, 4.40000); + EXPECT_EQ(tracked_objects.objects.at(0).shape.dimensions.y, 1.73071); + EXPECT_EQ(tracked_objects.objects.at(0).shape.dimensions.z, 1.0); } TEST(ParseFunction, CompleteFromFilename) From 5249a1347d5224e7d096ee8b8cb5ba190be9fb54 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 19:13:27 +0900 Subject: [PATCH 070/273] fix(autoware_behavior_velocity_run_out_module): fix clang-diagnostic-unused-lambda-capture (#9416) fix: clang-diagnostic-unused-lambda-capture Signed-off-by: kobayu858 --- .../src/manager.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp index 2a8bce46b9006..f294e698ba8c2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp @@ -160,12 +160,12 @@ void RunOutModuleManager::launchNewModules(const tier4_planning_msgs::msg::PathW } std::function &)> -RunOutModuleManager::getModuleExpiredFunction(const tier4_planning_msgs::msg::PathWithLaneId & path) +RunOutModuleManager::getModuleExpiredFunction( + [[maybe_unused]] const tier4_planning_msgs::msg::PathWithLaneId & path) { - return - [&path]([[maybe_unused]] const std::shared_ptr & scene_module) -> bool { - return false; - }; + return []([[maybe_unused]] const std::shared_ptr & scene_module) -> bool { + return false; + }; } void RunOutModuleManager::setDynamicObstacleCreator( From ce3d682553fa7130cd80995f59924fff92d428b7 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 19:13:42 +0900 Subject: [PATCH 071/273] fix(autoware_behavior_velocity_walkway_module): fix clang-diagnostic-unused-lambda-capture (#9415) fix: clang-diagnostic-unused-lambda-capture Signed-off-by: kobayu858 --- .../autoware_behavior_velocity_walkway_module/src/manager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp index d2cf4d39b2b2a..0f1a7509043b5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/manager.cpp @@ -45,7 +45,7 @@ void WalkwayModuleManager::launchNewModules(const PathWithLaneId & path) { const auto rh = planner_data_->route_handler_; - const auto launch = [this, &path](const auto & lanelet, const auto & use_regulatory_element) { + const auto launch = [this](const auto & lanelet, const auto & use_regulatory_element) { const auto attribute = lanelet.attributeOr(lanelet::AttributeNamesString::Subtype, std::string("")); if (attribute != lanelet::AttributeValueString::Walkway) { From e3aba5518222a76e22e975388aa8207c4d6ae8e2 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 19:13:57 +0900 Subject: [PATCH 072/273] fix(autoware_behavior_velocity_planner_common): fix clang-diagnostic-unused-const-variable (#9413) fix: clang-diagnostic-unused-const-variable Signed-off-by: kobayu858 --- .../src/utilization/path_utilization.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp index 2132d50d0ad52..17ea92022ea13 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp @@ -21,8 +21,6 @@ #include #include -constexpr double DOUBLE_EPSILON = 1e-6; - namespace autoware::behavior_velocity_planner { bool splineInterpolate( From 6717fb225cc5533a65bade6245ff47217ec5eb43 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 19:14:10 +0900 Subject: [PATCH 073/273] fix(autoware_behavior_velocity_planner): fix clang-diagnostic-format-security (#9411) fix: clang-diagnostic-format-security Signed-off-by: kobayu858 --- .../autoware_behavior_velocity_planner/src/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index 394412a508d41..5f4d0606abfc6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -233,7 +233,7 @@ bool BehaviorVelocityPlannerNode::processData(rclcpp::Clock clock) bool is_ready = true; const auto & logData = [&clock, this](const std::string & data_type) { std::string msg = "Waiting for " + data_type + " data"; - RCLCPP_INFO_THROTTLE(get_logger(), clock, logger_throttle_interval, msg.c_str()); + RCLCPP_INFO_THROTTLE(get_logger(), clock, logger_throttle_interval, "%s", msg.c_str()); }; const auto & getData = [&logData](auto & dest, auto & sub, const std::string & data_type = "") { From 7a19e8aa360f7849f871f15d9d971a4aff68739a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 20 Nov 2024 19:58:39 +0900 Subject: [PATCH 074/273] feat(simple_planning_simulator): add mechanical actuaion sim model (#9300) * feat(simple_planning_simulator): add mechanical actuaion sim model Signed-off-by: kosuke55 update docs Signed-off-by: kosuke55 * update from suggestions Signed-off-by: kosuke55 * calc internal state using RK4 results Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../simple_planning_simulator/CMakeLists.txt | 1 + simulator/simple_planning_simulator/README.md | 76 +-- .../docs/actuation_cmd_sim.md | 105 +++ .../simple_planning_simulator_core.hpp | 5 +- .../utils/mechanical_controller.hpp | 208 ++++++ .../vehicle_model/sim_model_actuation_cmd.hpp | 220 ++++--- .../vehicle_model/sim_model_interface.hpp | 14 +- .../simple_planning_simulator.launch.py | 7 +- .../media/mechanical_controller.drawio.svg | 602 ++++++++++++++++++ ...nical_controller_system_identification.png | Bin 0 -> 268250 bytes ...ing_simulator_mechanical_sample.param.yaml | 62 ++ .../simple_planning_simulator_core.cpp | 104 ++- .../utils/mechanical_controller.cpp | 352 ++++++++++ .../vehicle_model/sim_model_actuation_cmd.cpp | 265 +++++--- .../test/test_simple_planning_simulator.cpp | 82 +-- 15 files changed, 1817 insertions(+), 286 deletions(-) create mode 100644 simulator/simple_planning_simulator/docs/actuation_cmd_sim.md create mode 100644 simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp create mode 100644 simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg create mode 100644 simulator/simple_planning_simulator/media/mechanical_controller_system_identification.png create mode 100644 simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml create mode 100644 simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index 07e7e6b5ad169..6acb74342c90f 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -23,6 +23,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp src/simple_planning_simulator/utils/csv_loader.cpp + src/simple_planning_simulator/utils/mechanical_controller.cpp ) target_include_directories(${PROJECT_NAME} PUBLIC ${Python3_INCLUDE_DIRS} ${learning_based_vehicle_model_INCLUDE_DIRS}) # Node executable diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index 1d91d5e6149b4..cd362c0115358 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -65,32 +65,38 @@ The purpose of this simulator is for the integration test of planning and contro - `DELAY_STEER_ACC_GEARED_WO_FALL_GUARD` - `DELAY_STEER_MAP_ACC_GEARED`: applies 1D dynamics and time delay to the steering and acceleration commands. The simulated acceleration is determined by a value converted through the provided acceleration map. This model is valuable for an accurate simulation with acceleration deviations in a real vehicle. - `LEARNED_STEER_VEL`: launches learned python models. More about this [here](../learning_based_vehicle_model). -- `ACTUATION_CMD`: A simulator model that receives `ACTUATION_CMD`. In this case, the `raw_vehicle_cmd_converter` is also launched. + +The following models receive `ACTUATION_CMD` generated from `raw_vehicle_cmd_converter`. Therefore, when these models are selected, the `raw_vehicle_cmd_converter` is also launched. + +- `ACTUATION_CMD`: This model only converts accel/brake commands and use steer command as it is. +- `ACTUATION_CMD_STEER_MAP`: The steer command is converted to the steer rate command using the steer map. +- `ACTUATION_CMD_VGR`: The steer command is converted to the steer rate command using the variable gear ratio. +- `ACTUATION_CMD_MECHANICAL`: This model has mechanical dynamics and controller for that. The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves based on a 1st-order with time delay model. The `STEER` means the model receives the steer command. The `VEL` means the model receives the target velocity command, while the `ACC` model receives the target acceleration command. The `GEARED` suffix means that the motion will consider the gear command: the vehicle moves only one direction following the gear. The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V). -| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_A_G_WO_FG | D_ST_M_ACC_G | L_S_V | Default value | unit | -| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------- | :----------- | :---- | :------------ | :------ | -| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | o | x | 0.1 | [s] | -| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | o | x | 0.24 | [s] | -| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | x | 0.25 | [s] | -| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | o | x | 0.1 | [s] | -| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | o | x | 0.27 | [s] | -| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | o | x | x | 0.0 | [rad] | -| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | x | 0.5 | [s] | -| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | o | x | 50.0 | [m/s] | -| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | o | x | 7.0 | [m/ss] | -| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | o | x | 1.0 | [rad] | -| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | o | x | 5.0 | [rad/s] | -| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | o | x | 0.0 | [rad] | -| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | o | x | x | 1.0 | [-] | -| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | o | x | x | 1.0 | [-] | -| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | x | o | x | - | [-] | -| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | x | o | - | [-] | -| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | x | o | - | [-] | -| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | x | o | - | [-] | +| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_A_G_WO_FG | D_ST_M_ACC_G | L_S_V | A_C | Default value | unit | +| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------- | :----------- | :---- | :-- | :------------ | :------ | +| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | o | x | x | 0.1 | [s] | +| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | o | x | o | 0.24 | [s] | +| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | x | x | 0.25 | [s] | +| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | o | x | x | 0.1 | [s] | +| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | o | x | o | 0.27 | [s] | +| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | o | x | x | o | 0.0 | [rad] | +| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | x | x | 0.5 | [s] | +| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | o | x | x | 50.0 | [m/s] | +| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | o | x | x | 7.0 | [m/ss] | +| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | o | x | o | 1.0 | [rad] | +| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | o | x | o | 5.0 | [rad/s] | +| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | o | x | o | 0.0 | [rad] | +| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | o | x | x | x | 1.0 | [-] | +| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | o | x | x | x | 1.0 | [-] | +| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | x | o | x | x | - | [-] | +| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | x | o | x | - | [-] | +| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | x | o | x | - | [-] | +| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | x | o | x | - | [-] | _Note:_ Parameters `model_module_paths`, `model_param_paths`, and `model_class_names` need to have the same length. @@ -125,32 +131,8 @@ default, 0.00, 1.39, 2.78, 4.17, 5.56, 6.94, 8.33, 9.72, 11.11, 12.50, 1 ##### ACTUATION_CMD model -The simple_planning_simulator usually operates by receiving Control commands, but when the `ACTUATION_CMD` model is selected, it receives Actuation commands instead of Control commands. This model can simulate the motion using the vehicle command that is actually sent to the real vehicle. Therefore, when this model is selected, the `raw_vehicle_cmd_converter` is also launched. - -`convert_steer_cmd_method` has two options: "vgr" and "steer_map". If you choose "vgr" (variable gear ratio), it is assumed that the steering wheel angle is sent as the actuation command, and the value is converted to the steering tire angle to move the model. If you choose "steer_map", it is assumed that an arbitrary value is sent as the actuation command, and the value is converted to the steering tire rate to move the model. An arbitrary value is like EPS (Electric Power Steering) Voltage . `enable_pub_steer` determines whether to publish the steering tire angle. If false, it is expected to be converted and published from actuation_status in other nodes (e.g. raw_vehicle_cmd_converter). - -![vgr_sim](./media/vgr_sim.drawio.svg) - -```yaml - -``` - -The parameters used in the ACTUATION_CMD are as follows. - -| Name | Type | Description | unit | -| :----------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :--- | -| accel_time_delay | double | dead time for the acceleration input | [s] | -| accel_time_constant | double | time constant of the 1st-order acceleration dynamics | [s] | -| brake_time_delay | double | dead time for the brake input | [s] | -| brake_time_constant | double | time constant of the 1st-order brake dynamics | [s] | -| convert_accel_cmd | bool | If true, it is assumed that the command is received converted to an accel actuation value, and it is converted back to acceleration value inside the simulator. | [-] | -| convert_brake_cmd | bool | If true, it is assumed that the command is received converted to a brake actuation value, and it is converted back to acceleration value inside the simulator. | [-] | -| convert_steer_cmd | bool | If true, it is assumed that the command is received converted to a steer actuation value, and it is converted back to steer rate value inside the simulator. | [-] | -| convert_steer_cmd_method | bool | method to convert steer command. You can choose from "vgr" and "steer_map". | [-] | -| vgr_coef_a | double | the value of the coefficient a of the variable gear ratio | [-] | -| vgr_coef_b | double | the value of the coefficient b of the variable gear ratio | [-] | -| vgr_coef_c | double | the value of the coefficient c of the variable gear ratio | [-] | -| enable_pub_steer | bool | whether to publish the steering tire angle. if false, it is expected to be converted and published from actuation_status in other nodes (e.g. raw_vehicle_cmd_converter) | [-] | +The simple_planning_simulator usually operates by receiving Control commands, but when the `ACTUATION_CMD*` model is selected, it receives Actuation commands instead of Control commands. This model can simulate the motion using the vehicle command that is actually sent to the real vehicle. Therefore, when this model is selected, the `raw_vehicle_cmd_converter` is also launched. +Please refer to the [actuation_cmd_sim.md](./docs/actuation_cmd_sim.md) for more details. diff --git a/simulator/simple_planning_simulator/docs/actuation_cmd_sim.md b/simulator/simple_planning_simulator/docs/actuation_cmd_sim.md new file mode 100644 index 0000000000000..5219b20b6dbaf --- /dev/null +++ b/simulator/simple_planning_simulator/docs/actuation_cmd_sim.md @@ -0,0 +1,105 @@ +# ACTUATION_CMD model + +The simple_planning_simulator usually operates by receiving Control commands, but when the `ACTUATION_CMD*` model is selected, it receives Actuation commands instead of Control commands. This model can simulate the motion using the vehicle command that is actually sent to the real vehicle. Therefore, when this model is selected, the `raw_vehicle_cmd_converter` is also launched. + +## ACTUATION_CMD + +This model receives the accel/brake commands and converts them using the map to calculate the motion of the model. The steer command is used as it is. +Please make sure that the raw_vehicle_cmd_converter is configured as follows. + +```yaml +convert_accel_cmd: true +convert_brake_cmd: true +convert_steer_cmd: false +``` + +## ACTUATION_CMD_STEER_MAP + +This model is inherited from ACTUATION_CMD and receives steering arbitrary value as the actuation command. +The value is converted to the steering tire rate to calculate the motion of the model. An arbitrary value is like EPS (Electric Power Steering) Voltage. + +Please make sure that the raw_vehicle_cmd_converter is configured as follows. + +```yaml +convert_accel_cmd: true +convert_brake_cmd: true +convert_steer_cmd: true +``` + +## ACTUATION_CMD_VGR + +This model is inherited from ACTUATION_CMD and steering wheel angle is sent as the actuation command. +The value is converted to the steering tire angle to calculate the motion of the model. + +Please make sure that the raw_vehicle_cmd_converter is configured as follows. + +```yaml +convert_accel_cmd: true +convert_brake_cmd: true +convert_steer_cmd: true +``` + +![vgr_sim](../media/vgr_sim.drawio.svg) + +## ACTUATION_CMD_MECHANICAL + +This model is inherited from ACTUATION_CMD_VGR nad has mechanical dynamics and controller for that to simulate the mechanical structure and software of the real vehicle. + +Please make sure that the raw_vehicle_cmd_converter is configured as follows. + +```yaml +convert_accel_cmd: true +convert_brake_cmd: true +convert_steer_cmd: true +``` + +The mechanical structure of the vehicle is as follows. + +![mechanical_controller](../media/mechanical_controller.drawio.svg) + +The vehicle side software assumes that it has limiters, PID controllers, power steering, etc. for the input. +The conversion in the power steering is approximated by a polynomial. +Steering Dynamics is a model that represents the motion of the tire angle when the Steering Torque is input. It is represented by the following formula. + +```math +\begin{align} +\dot{\theta} &= \omega \\ +\dot{\omega} &= \frac{1}{I} (T_{\text{input}} - D \omega - K \theta - \text{sign}(\omega) F_{\text{friction}} ) \\ +\end{align} +``` + +In this case, + +- $\theta$ : Tire angle +- $\omega$ : Tire angular velocity +- $T_{\text{input}}$ : Input torque +- $D$ : Damping coefficient +- $K$ : Spring constant +- $F_{\text{friction}}$ : Friction force +- $I$ : Moment of inertia + +Also, this dynamics has a dead zone. +The steering rotation direction is different from the steering torque input direction, and the steering torque input is less than the dead zone threshold, it enters the dead zone. Once it enters the dead zone, it is judged to be in the dead zone until there is a steering input above the dead zone threshold. When in the dead zone, the steering tire angle does not move. + +Please refer to the following file for the values of the parameters that have been system-identified using the actual vehicle's driving data. +The blue line is the control input, the green line is the actual vehicle's tire angle output, and the red line is the simulator's tire angle output. +[mechanical_sample_param](../param/simple_planning_simulator_mechanical_sample.param.yaml) + +This model has a smaller sum of errors with the observed values of the actual vehicle than when tuned with a normal first-order lag model. For details, please refer to [#9252](https://github.com/autowarefoundation/autoware.universe/pull/9300). + +![mechanical_controller_system_identification](../media/mechanical_controller_system_identification.png) + +The parameters used in the ACTUATION_CMD are as follows. + +| Name | Type | Description | unit | +| :------------------ | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :--- | +| accel_time_delay | double | dead time for the acceleration input | [s] | +| accel_time_constant | double | time constant of the 1st-order acceleration dynamics | [s] | +| brake_time_delay | double | dead time for the brake input | [s] | +| brake_time_constant | double | time constant of the 1st-order brake dynamics | [s] | +| convert_accel_cmd | bool | If true, it is assumed that the command is received converted to an accel actuation value, and it is converted back to acceleration value inside the simulator. | [-] | +| convert_brake_cmd | bool | If true, it is assumed that the command is received converted to a brake actuation value, and it is converted back to acceleration value inside the simulator. | [-] | +| vgr_coef_a | double | the value of the coefficient a of the variable gear ratio | [-] | +| vgr_coef_b | double | the value of the coefficient b of the variable gear ratio | [-] | +| vgr_coef_c | double | the value of the coefficient c of the variable gear ratio | [-] | +| enable_pub_steer | bool | whether to publish the steering tire angle. if false, it is expected to be converted and published from actuation_status in other nodes (e.g. raw_vehicle_cmd_converter) | [-] | diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 76fdf5bdda6c9..3e54bca245f82 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -224,7 +224,10 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node DELAY_STEER_MAP_ACC_GEARED = 6, LEARNED_STEER_VEL = 7, DELAY_STEER_ACC_GEARED_WO_FALL_GUARD = 8, - ACTUATION_CMD = 9 + ACTUATION_CMD = 9, + ACTUATION_CMD_VGR = 10, + ACTUATION_CMD_MECHANICAL = 11, + ACTUATION_CMD_STEER_MAP = 12, } vehicle_model_type_; //!< @brief vehicle model type to decide the model dynamics std::shared_ptr vehicle_model_ptr_; //!< @brief vehicle model pointer diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp new file mode 100644 index 0000000000000..fcb8d41dd72b5 --- /dev/null +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp @@ -0,0 +1,208 @@ +// Copyright 2024 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. + +#ifndef SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ +#define SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ + +#include +#include +#include +#include +#include + +namespace autoware::simple_planning_simulator::utils::mechanical_controller +{ + +using DelayBuffer = std::deque>; +using DelayOutput = std::pair, DelayBuffer>; + +DelayOutput delay( + const double signal, const double delay_time, const DelayBuffer & buffer, + const double elapsed_time); + +double sign(const double x); + +double apply_limits( + const double current_angle, const double previous_angle, const double angle_limit, + const double rate_limit, const double dt); + +double feedforward(const double input_angle, const double ff_gain); + +double polynomial_transform( + const double torque, const double speed, const double a, const double b, const double c, + const double d, const double e, const double f, const double g, const double h); + +struct PIDControllerParams +{ + double kp{0.0}; + double ki{0.0}; + double kd{0.0}; +}; + +struct PIDControllerState +{ + double integral{0.0}; + double error{0.0}; +}; + +class PIDController +{ +public: + PIDController(const double kp, const double ki, const double kd); + + [[nodiscard]] double compute( + const double error, const double integral, const double prev_error, const double dt) const; + + void update_state(const double error, const double dt); + + void update_state( + const double k1_error, const double k2_error, const double k3_error, const double k4_error, + const double dt); + + [[nodiscard]] PIDControllerState get_state() const; + + void clear_state(); + +private: + double kp_{0.0}, ki_{0.0}, kd_{0.0}; + PIDControllerState state_; +}; + +struct SteeringDynamicsParams +{ + double angular_position{0.0}; + double angular_velocity{0.0}; + double inertia{0.0}; + double damping{0.0}; + double stiffness{0.0}; + double friction{0.0}; + double dead_zone_threshold{0.0}; +}; + +struct SteeringDynamicsState +{ + double angular_position{0.0}; + double angular_velocity{0.0}; + bool is_in_dead_zone{false}; +}; + +struct SteeringDynamicsDeltaState +{ + double d_angular_position{0.0}; + double d_angular_velocity{0.0}; +}; + +/** + * @brief SteeringDynamics class + * @details This class calculates the dynamics which receives the steering torque and outputs the + * steering tire angle. The steering system is modeled as a spring-damper system with friction and + * dead zone. + */ +class SteeringDynamics +{ +public: + SteeringDynamics( + const double angular_position, const double angular_velocity, const double inertia, + const double damping, const double stiffness, const double friction, + const double dead_zone_threshold); + + [[nodiscard]] bool is_in_dead_zone( + const SteeringDynamicsState & state, const double input_torque) const; + + [[nodiscard]] SteeringDynamicsDeltaState calc_model( + const SteeringDynamicsState & state, const double input_torque) const; + + void set_state(const SteeringDynamicsState & state); + + [[nodiscard]] SteeringDynamicsState get_state() const; + + void clear_state(); + + void set_steer(const double steer); + +private: + SteeringDynamicsState state_; + const double inertia_; + const double damping_; + const double stiffness_; + const double friction_; + const double dead_zone_threshold_; +}; + +struct StepResult +{ + DelayBuffer delay_buffer{}; + double pid_error{0.0}; + SteeringDynamicsDeltaState dynamics_d_state{}; + bool is_in_dead_zone{false}; +}; + +struct MechanicalParams +{ + double kp{0.0}; + double ki{0.0}; + double kd{0.0}; + double ff_gain{0.0}; + double dead_zone_threshold{0.0}; + double poly_a{0.0}; + double poly_b{0.0}; + double poly_c{0.0}; + double poly_d{0.0}; + double poly_e{0.0}; + double poly_f{0.0}; + double poly_g{0.0}; + double poly_h{0.0}; + double inertia{0.0}; + double damping{0.0}; + double stiffness{0.0}; + double friction{0.0}; + double delay_time{0.0}; + + // limit + double angle_limit{0.0}; + double rate_limit{0.0}; + double steering_torque_limit{0.0}; + double torque_delay_time{0.0}; +}; + +class MechanicalController +{ +public: + explicit MechanicalController(const MechanicalParams & mechanical_params); + + [[maybe_unused]] double update_euler( + const double input_angle, const double speed, const double prev_input_angle, const double dt); + + double update_runge_kutta( + const double input_angle, const double speed, const double prev_input_angle, const double dt); + + void clear_state(); + + void set_steer(const double steer); + +private: + DelayBuffer delay_buffer_; + PIDController pid_; + SteeringDynamics steering_dynamics_; + const MechanicalParams params_; + + [[nodiscard]] StepResult run_one_step( + const double input_angle, const double speed, const double prev_input_angle, const double dt, + const DelayBuffer & delay_buffer, const PIDController & pid, + const SteeringDynamics & dynamics) const; +}; + +} // namespace autoware::simple_planning_simulator::utils::mechanical_controller + +#endif // SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp index b78ec8ccd538a..25fac72d283ee 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp @@ -19,15 +19,20 @@ #include "eigen3/Eigen/Core" #include "eigen3/Eigen/LU" #include "simple_planning_simulator/utils/csv_loader.hpp" +#include "simple_planning_simulator/utils/mechanical_controller.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include +#include #include #include #include #include +using autoware::simple_planning_simulator::utils::mechanical_controller::MechanicalController; +using autoware::simple_planning_simulator::utils::mechanical_controller::MechanicalParams; + /** * @class ActuationMap * @brief class to convert from actuation command to control command @@ -101,10 +106,8 @@ class BrakeMap : public ActuationMap class SimModelActuationCmd : public SimModelInterface { public: - enum class ActuationSimType { VGR, STEER_MAP }; - /** - * @brief constructor (adaptive gear ratio conversion model) + * @brief constructor (only longitudinal) * @param [in] vx_lim velocity limit [m/s] * @param [in] steer_lim steering limit [rad] * @param [in] vx_rate_lim acceleration limit [m/ss] @@ -120,49 +123,15 @@ class SimModelActuationCmd : public SimModelInterface * @param [in] steer_bias steering bias [rad] * @param [in] convert_accel_cmd flag to convert accel command * @param [in] convert_brake_cmd flag to convert brake command - * @param [in] convert_steer_cmd flag to convert steer command - * @param [in] accel_map_path path to csv file for accel conversion map - * @param [in] brake_map_path path to csv file for brake conversion map - * @param [in] vgr_coef_a coefficient for variable gear ratio - * @param [in] vgr_coef_b coefficient for variable gear ratio - * @param [in] vgr_coef_c coefficient for variable gear ratio - */ - SimModelActuationCmd( - double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, - double dt, double accel_delay, double accel_time_constant, double brake_delay, - double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, - bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd, - std::string accel_map_path, std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, - double vgr_coef_c); - - /** - * @brief constructor (steer map conversion model) - * @param [in] vx_lim velocity limit [m/s] - * @param [in] steer_lim steering limit [rad] - * @param [in] vx_rate_lim acceleration limit [m/ss] - * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] - * @param [in] wheelbase vehicle wheelbase length [m] - * @param [in] dt delta time information to set input buffer for delay - * @param [in] accel_delay time delay for accel command [s] - * @param [in] acc_time_constant time constant for 1D model of accel dynamics - * @param [in] brake_delay time delay for brake command [s] - * @param [in] brake_time_constant time constant for 1D model of brake dynamics - * @param [in] steer_delay time delay for steering command [s] - * @param [in] steer_time_constant time constant for 1D model of steering dynamics - * @param [in] steer_bias steering bias [rad] - * @param [in] convert_accel_cmd flag to convert accel command - * @param [in] convert_brake_cmd flag to convert brake command - * @param [in] convert_steer_cmd flag to convert steer command * @param [in] accel_map_path path to csv file for accel conversion map * @param [in] brake_map_path path to csv file for brake conversion map - * @param [in] steer_map_path path to csv file for steer conversion map */ SimModelActuationCmd( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double accel_delay, double accel_time_constant, double brake_delay, double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, - bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd, - std::string accel_map_path, std::string brake_map_path, std::string steer_map_path); + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path); /** * @brief default destructor @@ -179,7 +148,7 @@ class SimModelActuationCmd : public SimModelInterface */ bool shouldPublishActuationStatus() const override { return true; } -private: +protected: const double MIN_TIME_CONSTANT; //!< @brief minimum time constant enum IDX { @@ -198,39 +167,29 @@ class SimModelActuationCmd : public SimModelInterface GEAR, }; - const double vx_lim_; //!< @brief velocity limit [m/s] - const double vx_rate_lim_; //!< @brief acceleration limit [m/ss] - const double steer_lim_; //!< @brief steering limit [rad] - const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] - const double wheelbase_; //!< @brief vehicle wheelbase length [m] - - std::deque accel_input_queue_; //!< @brief buffer for accel command - std::deque brake_input_queue_; //!< @brief buffer for brake command - std::deque steer_input_queue_; //!< @brief buffer for steering command - const double accel_delay_; //!< @brief time delay for accel command [s] - const double accel_time_constant_; //!< @brief time constant for accel dynamics - const double brake_delay_; //!< @brief time delay for brake command [s] - const double brake_time_constant_; //!< @brief time constant for brake dynamics - const double steer_delay_; //!< @brief time delay for steering command [s] - const double steer_time_constant_; //!< @brief time constant for steering dynamics - const double steer_bias_; //!< @brief steering angle bias [rad] - - bool convert_accel_cmd_; - bool convert_brake_cmd_; - bool convert_steer_cmd_; - - AccelMap accel_map_; - BrakeMap brake_map_; - ActuationMap steer_map_; - - // steer map conversion model - - // adaptive gear ratio conversion model - double vgr_coef_a_; - double vgr_coef_b_; - double vgr_coef_c_; - - ActuationSimType actuation_sim_type_{ActuationSimType::VGR}; + const double vx_lim_{0.0}; //!< @brief velocity limit [m/s] + const double vx_rate_lim_{0.0}; //!< @brief acceleration limit [m/ss] + const double steer_lim_{0.0}; //!< @brief steering limit [rad] + const double steer_rate_lim_{0.0}; //!< @brief steering angular velocity limit [rad/s] + const double wheelbase_{0.0}; //!< @brief vehicle wheelbase length [m] + + std::deque accel_input_queue_{}; //!< @brief buffer for accel command + std::deque brake_input_queue_{}; //!< @brief buffer for brake command + std::deque steer_input_queue_{}; //!< @brief buffer for steering command + const double accel_delay_{0.0}; //!< @brief time delay for accel command [s] + const double accel_time_constant_{0.0}; //!< @brief time constant for accel dynamics + const double brake_delay_{0.0}; //!< @brief time delay for brake command [s] + const double brake_time_constant_{0.0}; //!< @brief time constant for brake dynamics + const double steer_delay_{0.0}; //!< @brief time delay for steering command [s] + const double steer_time_constant_{0.0}; //!< @brief time constant for steering dynamics + const double steer_bias_{0.0}; //!< @brief steering angle bias [rad] + + bool convert_accel_cmd_{false}; + bool convert_brake_cmd_{false}; + bool convert_steer_cmd_{false}; + + AccelMap accel_map_{}; + BrakeMap brake_map_{}; /** * @brief set queue buffer for input command @@ -284,6 +243,24 @@ class SimModelActuationCmd : public SimModelInterface */ void update(const double & dt) override; + /** + * @brief calculate derivative of longitudinal states + * @param [in] state current model state + * @param [in] input input vector to model + * @return derivative of longitudinal states except steering + */ + Eigen::VectorXd calcLongitudinalModel( + const Eigen::VectorXd & state, const Eigen::VectorXd & input); + + /** + * @brief calculate derivative of lateral states + * @param [in] steer current steering angle [rad] + * @param [in] steer_input desired steering angle [rad] + * @param [in] vel current velocity [m/s] + * @return derivative of lateral states + */ + virtual double calcLateralModel(const double steer, const double steer_des, const double vel); + /** * @brief calculate derivative of states with time delay steering model * @param [in] state current model state @@ -301,7 +278,35 @@ class SimModelActuationCmd : public SimModelInterface void updateStateWithGear( Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear, const double dt); +}; +class SimModelActuationCmdSteerMap : public SimModelActuationCmd +{ +public: + SimModelActuationCmdSteerMap( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, std::string steer_map_path); + +private: + double calcLateralModel(const double steer, const double steer_des, const double vel) override; + + ActuationMap steer_map_; +}; + +class SimModelActuationCmdVGR : public SimModelActuationCmd +{ +public: + SimModelActuationCmdVGR( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, double vgr_coef_c); + +protected: /** * @brief calculate steering tire command * @param [in] vel current velocity [m/s] @@ -321,6 +326,75 @@ class SimModelActuationCmd : public SimModelInterface * @return variable gear ratio */ double calculateVariableGearRatio(const double vel, const double steer_wheel) const; + +private: + double calcLateralModel(const double steer, const double steer_des, const double vel) override; + + // adaptive gear ratio conversion model + double vgr_coef_a_; + double vgr_coef_b_; + double vgr_coef_c_; +}; + +class SimModelActuationCmdMechanical : public SimModelActuationCmdVGR +{ +public: + /** + * @brief constructor (mechanical model) + * @param [in] vx_lim velocity limit [m/s] + * @param [in] steer_lim steering limit [rad] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] + * @param [in] wheelbase vehicle wheelbase length [m] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] accel_delay time delay for accel command [s] + * @param [in] acc_time_constant time constant for 1D model of accel dynamics + * @param [in] brake_delay time delay for brake command [s] + * @param [in] brake_time_constant time constant for 1D model of brake dynamics + * @param [in] steer_delay time delay for steering command [s] + * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] steer_bias steering bias [rad] + * @param [in] convert_accel_cmd flag to convert accel command + * @param [in] convert_brake_cmd flag to convert brake command + * @param [in] convert_steer_cmd flag to convert steer command + * @param [in] accel_map_path path to csv file for accel conversion map + * @param [in] brake_map_path path to csv file for brake conversion map + * @param [in] vgr_coef_a coefficient for variable gear ratio + * @param [in] vgr_coef_b coefficient for variable gear ratio + * @param [in] vgr_coef_c coefficient for variable gear ratio + */ + SimModelActuationCmdMechanical( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, double vgr_coef_c, + MechanicalParams mechanical_params); + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double & dt) override; + + /** + * @brief update vehicle states with controller + * @details In updateRungeKutta, calcModel is called four times, but the internal state of PID and + * Dynamics should not be updated. Therefore, a method is prepared to update the internal state + * only once at the end without using the updateRungeKutta of the interface. + */ + void updateRungeKuttaWithController(const double dt, const Eigen::VectorXd & input); + + /** + * @brief set state + * @details This model needs to update mechanical dynamics state too + * @param [in] state state vector + */ + void setState(const Eigen::VectorXd & state) override; + +private: + std::unique_ptr mechanical_controller_; + double prev_steer_tire_des_{0.0}; // }; #endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp index f8d682a6e851c..5ca886b1b5847 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp @@ -64,12 +64,6 @@ class SimModelInterface */ void getInput(Eigen::VectorXd & input); - /** - * @brief set state vector of model - * @param [in] state state vector - */ - void setState(const Eigen::VectorXd & state); - /** * @brief set input vector of model * @param [in] input input vector @@ -96,6 +90,14 @@ class SimModelInterface */ void updateEuler(const double & dt, const Eigen::VectorXd & input); + /** + * @brief set state vector of model + * @details In some sim models, the state member should be updated as well. Therefore, this + * function is defined as virtual. + * @param [in] state state vector + */ + virtual void setState(const Eigen::VectorXd & state); + /** * @brief update vehicle states * @param [in] dt delta time [s] diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index 9b31926a53d57..aed088de9fd22 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -106,10 +106,9 @@ def launch_setup(context, *args, **kwargs): # Determine if we should launch raw_vehicle_cmd_converter based on the vehicle_model_type with open(simulator_model_param_path, "r") as f: simulator_model_param_yaml = yaml.safe_load(f) - launch_vehicle_cmd_converter = ( - simulator_model_param_yaml["/**"]["ros__parameters"].get("vehicle_model_type") - == "ACTUATION_CMD" - ) + launch_vehicle_cmd_converter = "ACTUATION_CMD" in simulator_model_param_yaml["/**"][ + "ros__parameters" + ].get("vehicle_model_type") # 1) Launch only simple_planning_simulator_node if not launch_vehicle_cmd_converter: diff --git a/simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg b/simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg new file mode 100644 index 0000000000000..a595b2479d4c6 --- /dev/null +++ b/simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg @@ -0,0 +1,602 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Desired Steering Whell Angle +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ PID +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ FF +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+
+ + Power steering +
+
+
+ (polynominal) +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
Driver Torque
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Steering Torque +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Delay +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Steering Dynamics +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ VGR +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ VGR +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Limiter +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Observed Steering Tire Angle +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Observed Steering +
Wheel Angle
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Mechanical Controller +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Simulator Model +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Desired Steering +
Tire Angle
+
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/simulator/simple_planning_simulator/media/mechanical_controller_system_identification.png b/simulator/simple_planning_simulator/media/mechanical_controller_system_identification.png new file mode 100644 index 0000000000000000000000000000000000000000..f96a5848b7fbc04269a29335138fe474e2b7b6fe GIT binary patch literal 268250 zcmd?RbzGL&+6IbaqL>(nfq@{Pl(d9N2!gb;khhJ{%^lszNyY0?jwv)FsuyfS5(Wfx9ur${{ZmVmf zuWw;%WNA0NvPc*&I$^AE+3u{3zP6pQrNsdSV{?7{kb;7fos+94=M@LXkMP^ z4{&n+2))kE*K^y8o3}SUP$q>Vor2;3g~Ykj3Qpla+Z^2#6qlAq8z=N?Lhpa0KC|u2 zZ|8oy_QhxQ;p9Wtb@Z)O76y_MSaNk5743HH@+=!*{@U=`L1We1SYxB7;xY%{pE`3! zd^j|;osM;!Tdwtb*_gWsoxdQLZIw`O>j}pn@2uL#IkMXQgD6wh%>{QSvYGT>c9V@yZfSya21{W*|RGh z+w6BWs@rb#-n4J7^yARLz#$QlsQ%jc+AK@0cg4l{-R2N=8_FoRu{-f?=XYtm#|JD2 zeKwvPsGk_9_qiCxvsgPH{NTapM6FDQ^SFUJYon*2_r8-3>>dkFk)BJl%h_yy7ApV4 z+1|*je->Fd{{>0O(36g=larIJE`urLEf0&`yL9Q&DRc9b_%_2R_m5ajkC%I*HCT6v zMhA$|xo^Mmb|lExxo)hdoQa9)ZKqYbNjg8`_jXi8K)l=VPZx`M|*mDwr}5V zx8bYcYKh&=ZE6f*3B2wN3~*{JdP{*Rgu_>fqquONxpgB-sjXRvXcCa0Ilrs)tK6on8!h-n4i?NQw-`XsszGWD0KI!-?CNYsxL_}n6qW`R$TYj(Tpp3}kb~ZM) zGiT0x%{1M`6Xq9iSnQ=?)qY>m!`0Q*b`B15SZ-I>lbgJ62)RyuX>Putr$@hX4b_|W z_VyE+*47+qugylyhO493;$o?2xo&rKbWo>y*YIoB?vSE| zBMd>5SD!yW#vmR3X=7b^6_-<#UR$(XaCYVw78a)3FZd`uotm z!66}CLqivfJQmk&-fT$TXy;BH&QNg~8AfjI9Wy*L@^W%#w6zarW@ge*t*M&h-@B8Y%HXhxxp`0J$zggv zzDFVpotx?D=_#xlR17)XW~^BAN6zeb={qPVFON?c{i&>}S-DHg?XA`vIy&qF$u!LZ!TDFOUZvwBaKpSm=p5wa3`|W;rA~F1l-#g~*W$fJR!~4d zr?XIIR#t{}muRa6@5;5C-uK(R)GyyzIQwIdfPg@H%MksMBLRVd-<^LIna)oQy?XuH zrpu4l1}m`QOOdDN*w~ohuq_2X`=dn`_3qsgVq$C6vMg{jZ#{W(;I5C4v4sT#1B2Jk zpJw;=^1s72Ha0Rkz{M5(^sKi|Mw6951i9FxB<3}n_TG+)it45L=DF;?W+Ux6b@f&b z+n+yw#$;zddiLzlz~JDE%g1hddj~~C_*EE0r>5RRHM zDkblTuKpBvF|4m8iw!q7a?f@DHK)m{;C@M=lMgne6zg$nv(wOU>aEjq8(qzoKk}PJ z)*eq!&w+sfc3QtytKyB_KYsi+LT;Srl3RX${>b!n@27ynGjnq`wHJA-v3zI>{(@uc zDk>_vySqDVa!B2ebi5_q?W-BjN8jCN(J9i3mIP*JXY~vWbTU z$E9DJHJ!1s;S`PDn$=QanpW^JKFXu))-FwPTiX+u4BL0@A~VfuwkKp|x^Bs)NT=_V z%q%Q-?%sW8#xvd@A2o)?jw@Q|@)CI*7Un!$Fztl@PghNGa&?v0)RabJ$1I&}y}dlu zVkwV~I?-P{IyNQ{M~Bbbz?OeXN{XsB?&3)X-z%J$rk@_Ja-8*myD{ zI@pq*A9HUAtN4hmTA5KLTz-4&VSGYeV`GM8yRg@0I%#q7bss)_Ks}Fo9654?o`InT4GAsN$igBnJ$(x{Nu-yS-f&?Udaw>V z&DV78mHxtWNB8a9ckcZ87k2$}sBxQ`#`owW7_+I2;=f^UzP+(oSX@nQ55|oSKIL;5 z@8;-g@k^Jsu!i^mZM@9L7@eFHimNhjc`b`eIlEb?o6=+Nj&0lCeGWa5Gnkrp86Do) z*_ooQu8!UEn;;6w2t&8y?G0aA?z{N=dtbg>8XF%cFI`7TiRnubQhwgbiXBsMW@hG+ ztnAyBn*~p)sO&~lLPz-W_3J0xk(|C~K7D_wDUbj~~;1HaKDXxw$ia(f(u;`U_1x>J3jzO8P!sv@C@6)zjA> z#lIVCHci_~O?{)@BsMzwhOqnGmYq8tTAyGn>`F;V0eqm|w(X39LNH_aR2wtn_>YRi zXldHTUe&FwpZ8eizeOkbR91#6B}KQiIG^+VE(@0GS$=*vfjR2xpDTFVKL<0(_YDl_ z^w-2bSIO`yq4R8|UP4(IU=n_g5?RhJX|Jn$54akPs<`pm^2K*o0;6%S(<6i;EngQa@X={DB%Q3MQ3)Te*^njjb2+Q?Kiz-}{o1 zuAZLr8XEh&H`59Kvi%E!U*`WSN$3s+I5of|&!7J0`dlOL;qBY&3y55IoB4BW^6+Pvi>5YsvA=^ZU&Xu zD>}OTMGUb0rNVfIvOE2wdA&F9=6o-|;=2=S?{a|)H()hoZM;k`E}^wTjr07V&bUe*c>6q9=K#-K)LA9@#B7DV>TF#q~NnhKkh+g`0nKol#Lec?CljZ zG-M3pG1uvQcPl0~mcw~WPo^Ce)#}h<9upH|)%WG#kI$jSj8Sf9+6&z=^T?XMe$BJr zV@4a;jER|92ONV@Xf58~sXIVy1`u1Q(?3Nm>m`5&zOsz6@-EYc=T9*q*Y0<^dh_Ng z4Dy781U`#;%B#oKUSHt}6M7mpyhqT99dieu*J*zXU`B|B!|o7G7p65guA!&hKJT+L z0IWt+bH8Q5XRj2wQALuhK7$Phx3b3TjJv4Bl%PQYn0J8 zFvz~YZn5aXq%pu6nY9;2h%C=mVU}{b&)NNSIGL=R_TyLHu(0+_F&fb68*4bw6{m*V zWzL;jMRDuat-X9!SAp-*pq)_WckbNjM4`TIX$eEORcBSs8W3sMYR66AdF=9=`QaiN zH2U4UcavtiV&xjUWVs1F^`#aPe zVHE%XFU^`bzj@4?$4N(&-K3<(Xfykk9~x#^82aiJ7x^Km*ZZ2--`Uz(?@h7T8@MAc z+-Ao-T`T`&|28&^OA{)8N(|jvbr_(e{gB!n=`03Z=mrqzRxX;`u~~TL0Q%_HA&2Km zECw07y^F6EcfM(C3;}<vmHxpi(J_r!VVbd-CEIRs*pP&B1 z%&3C0vOK0yXR&u_RTbHVhZz~YKYbEkLq+ojxQKGyI=+5YOu3OxZ#quUGD5)p{EqPQ zhH#rU;2Soin1d_zMmX-bwzfvwVt1J^0ON)<-^YYun%jq<71>95ug#a9{Zv9~g zIIymq^&B%6t{puCPUf$;`JG#1Vl=qAYmQaA88rQ~c-L*yTXrRj9=5615F@s7X0;payj zKw=nA*Xm7rNXG}X$6fm^9dy=V_*+Gq=b~vx%asct!Q{H!=Ozx))8Cw!uw%{bI|S7F z4l}(e*Pg}C&rjW^^axPd*4?{Hfeb%YRtope85$aPS@B(dp|g5uXb59wtXhnYyZ}fE zZ4~o@(5;444M~h}&_x33hKAf*g{i5jLwPOtlkI`}k7TAPTIgX@d1bU!I)41-IJl%P zfZjPVv7kqf#HFP-K^Fm~55ymEi8t14)S3R(1{fMS@m2aGpog+@3Fc5`j6_iO%y%E> zj%#aCpN60d7%D#<@)$>~CknFBL+g{3$@*i{ad2?lymgBM3eI=zqJ{A)Y+5}4e|P=ul@SGRBU4kty`UUmcM1;qi5}kMy;4M^C}?UP4O>n{rF3z+ zT?P!80@Rv|oBIXGWKC_YP>FF?OP=CyqvPYnLk_idb?4A0?d|O+el}&OQ5@#r7`>@` zGC~@9fVhW;Fy_R7(w!%nnGbODQR#iv(Iu40410HM*>bhbLWCiG%pI5;1iI6T4}a&~ zYYjk;;h30|G$y!{hUV*WGf*YU_3PgeQAHV?4CEHWuI=NU+qXvqry*u&X=wqW2~}mj zz4E4{q$Hyq!q+1qR~`U-)6^WVzCI&J7eb1Hg)9OB%_j=0joz1+`(O-1O~6=t+i$mR z_wN4P?M7SxGgdYBE3$vSEYBWDN}d@=PNU(oI)EW%@a`rhnk_iqE_JIF00+l3^B;-r zcfN`CU{LY+!}3Da^4_c>G(fy5gp`uDC5)FVnW}k0n>#x@+ZtM{sy2HUzeTkfSz7i2 zAb;$!8AW}J=d~~1LtnB0{9rAZkW*Dv#b(rAT9`eip8ch^q)|n#cfii+myaD&d3h5I^5K3Vmn#^z3!^1uClQc@J&IvrJ(!YZ zvozaF$9q+mGZbp-_jeoE=-Jpd16gC2XBbp`2Y@?#@?_Y=#6(vm%1-8gxSn;s^!bbgM1o1inrWvE)iOe7GAvs_mPh znyM;|h=(9YUHtiF5k52!SU(8?Wb574g zwWCZ-odjaUg;`*Qult}`KUxy?qrFwCN5G!cBlf3iSKa|{15$KY@j>gm+B*tlZ}H$1 zDcrO)Mh1p8$@O>JEP8?Je&AI^;JCG6mrc9-H1x6xj0fmY7#=r(Hs`WSrrWsZmju?V zT17-}!bZXS2uCgg0zpkej|3S5i~50YBoG(qU14w-3KUe7#|;e)7S|#$WT9G1=S~6Y zzR)chgS>g``t{#%VIV=>;kK2dpHJ}cJS14QL}V#|AnPk{fBRLm>~a12bsBz~ZVvbT zLX1)j)I<~Q?$#q)aA_i51Y(qX&Flh;{~kY4+(|UpHs-tGM`u>HN3Mh>2KA4_@t1nl zeE+YuJWs3E=(H}t#uKhnW@tot=F`*DB`qy`pjlw|Wi?h;KY9Frvi0o+zNH+`SxnA< z|C(jQ?ajd4EGsKZNJ)t;ER2MBmu}N@!DXWFGy%dWBvk(;dHJ(w#u$hMx`7x%{amqP z1vU}&o;{LPkwQZ4_eAtQZNcQZoab;HGe0|l~gW2#X9#a<|gdeD~CJr^gBX%*(TRH2hM$D=`U_+W#)knWQi76>P z*hu+v1Idi7V6gZ9Q1D*93B@%|L=ah-<~{udJTVCmM?Kla&~pqeQ}u& z$_-XkK}qSQ&WH7YwM%T1U4w&?N=iEkse_IL-R35#ke>38<&HwJ;?3mpM!$amBipij zH>I0v^b#~5BFEx=fPrkA^h2~cL#1g(`kOKs(Z_Uvw(>!)@fmVjS~8Fg=sXuV*oqc7 zvAco#T&DP;e9*a#tbm@oSJ>?lO8G9l2;y1z`)>vTgkUMFrR87Td8PYP07kD(_ouA@ z>hkf@`XIHD?4qE#7z<9$&ikm}&k0*vTH4s!q8itEE_BghjrB2ZfHA1ntbFm}1;CB0 ztZZkZsO^M3ZoVHr0@&vAv7N$;6Y|*7eE4_JLJfwRGexqOP&zSiHS#BFB=Z4UCWhPF zM7m=iWB)&W^5p9M`}gHl7vJf; z*aCup8A9af*RLPmSi5-)-89OI?#5fp?vj2xIYq_upxW(j;~T4lrq#0?c)~U&*AMV} zLQH(oG6eVttL+S4fpR5vijf4d%)`TjP)0Bl+j4)UcD;sAc)2?m{t@C z6U>!45FkiaLE&a`C!dA=*7({|kO$~b-;MRjKu_+gBnuY`hzPrA9!y^$-VMrvzB*I{)rKLTJVT!qef`HBO)@$RQ%fP!@?vp!! ze=|wR2qpRDGuRokWzG;_+T>#^{H4u!e094AqfAGl}E}RE?TKyz3@eVx4AC(d1 zS68fjBw)|%3GMADD=Pz>B4{(71CzgS&0zdF^S|;453g6&npDU~x9$N_j*E^imT%LC zs0F1V=<#Eh)+N%``eQ?g=Zv=i$AhL(g|0(jC5Xq;TmD5B6lh;t9xpK)h{gkM`|;yP z>esxqeuOPBKSr0Y{`%EP>Vf~icr^sB3-wT*|Oyn z)F_AozI%A@jaP|8-JxcD=|1nU->G8-ab#-y^}ud$6QgQ$cl~?zYzZ31wML@{}>`C)wlZTX_+18nv|n6Ckmmpt1pw?0I{`{6s%`>H(L3IOwA3m? zZc$ND!AP)I3wi$hxrHJ%niceF2;9TULI{&75OHMcVK>gUN=+KI!7J119xZ!GP3*U+4;pK8yg$Q zIv;Rn9rD1(uAn~DZ7aCj&TJKH>_TP6KYhBw=fk@M*=Q(icMaS2Zu0Ks1}*AGhf~&c zJ_4=roe|fzEnA4~gVM0Gx7W^Sy6x+$2aFiW%@ry|h%F{XenEkMs3mkqj6$i$Tz6t( z=&NQec)}#a#Sa`mz7Y!qsT4Sgl7IiwqK_mx2KP(9#Y2rui3cM$O`%Ld=PYi-QX)SXD8qxf!>eicWa1&xh~)-u@Oc7cc4~RDfCq ze?JSLhFbw*PIM;lvXSxe!$Ly)P|~G(L~cfK1bBv+WWbDX;Kc6Q zq*2^m2nb*5>uwDcdF-X@m>Kp=Q9Ffmbr?^H&dbjCQ9kdf(iESlHIN`L1c3!n#u5%|uh%_1Hn zb#}a$djI~)cege`4VbU)J@6+nJ9J1SirVv5$e+mfHn#uF&x|Ukfy8(tc=KT4Xag8c zr%~Jec@dyjt3Pspl^Vu7Dt`yf$PaYMYwwU@=gM zJw3N742q4omgsGo5as{>68w4*^@FAK&!zj% z-*va^U=>H&KY`rh8(%4=$CEBwu2MBJhpU!ZNUc;2*hzW*t+U2{juw>elmXBV?!LRQ>Q3U#bAU{ zt{3pp@i*biU{u39+(JW>U>c4*8pj_B1w3ici>JT;NOr;wo{zQTzy|D(Os@FF#7PJ#@(CBj22}K3X3dLN2tRKi&!00e%HGsM&|8LiB`#`GoG5@a9>I%=`Yuf-iq=3-!qA{lL z-Mc5he~CS^=G$K{@6X?N`)YFyJhTn)e25$L`-qWoZ;#Ix`_Co)_n!hzs005%FBO^Q zT1w7ov%vaT3q&xQ*H%}LMz3OCQpB=VR#ryov;MEN<|j}1oEO0Wkd7f?i=W>L!ocgG z{ZkOQx^~mv8QJ39MY9!_GhKAcGtm>6#>OzE!Amsq9A3CiTY$nNz_KX&aXts;hZUkB zqjmB!5hFRwM~`;E5|4fUoa!p%de^1p60GP41U>|Nx1WMen$>EvA+IeL=hr+m6fH-MGJ`5!&@}F5t}a`_M};Bc7QjX2NGH7@&d1aZ-^sb zb^Wz@mie-}Js~6KPc@r9*D8vHwuG6An|}q0xVrmfy-3-k_-J5f652tKfpB385GSac z+{C{Y8TbmeOSMlR_yLPDnaC6`U%qsLCP;_`#^2?X20Hsq?Xmx>4i*~Gr_I`OA0Vm8 zY1(kii)!~7_%%qkeCV{ggtS$2rYU5>ZUohi2nvSpK4AbzK}Y~`rZO^u-oHQRwQ1j7 z)SE?C7{ofI6xH)!=ID0Bq@bfCRw;zqxY*d$L8b4B0xamvIoOz1g7Ikfl^yY=rb73V zpq`K=x@>Z21niE2MN@#$1w=(vLB_!V(?wo~1PLU97`ATN@?~fSkwIhtxezE^_`zFr zkcDLf7zf__=+UDTPr#{xze#=%1#%mn2$&AKDuyUrHt0WLWn~u-A~^$s;aa=f5j%5M1w$qAo~K; z35}(+qGEDy2|^O5VOoGQBU1s}ZAf29+Sf)!)~5;KYd_IIo~=Dv*spk3q2q zmX02a)Fr+}57IDC3JM}V`0THfiduq5K@{Lg*X|Dor4Wu-11FU=dh zxv8~<=3O@XiXuLY4SB9;Zt*wQ&0HFu3Nl6#4B9*{?GMNV+`0mVat}p4kn)vF7wbLJ^2ekYV(zU|N$P+q-w4!J#8T21FnpKuE*Nek^Azl9H3#hDti7_SzRY zCl1U}-FI}5>B)6}jyM?t=H;?~^M(zio&eggn59tD2>d^K^tQjq(jzD-Hf{Eevane2 z-3cWcZjVAtP}5^pACB<_v>^C%P~=x36pbBm5n&SqpidIW42y~6?1<)s*d_Ev2nxNH zp7VPQGD3lTN$3Eon6#LfHzN%RSQ%7?1GoObyL>=R0`G!cs}#ENV>gp+Pf~!;ZoYi^ zatdKhq9uT;fqL$nc4j?x?7bNeM)loJK1PxzCd=1{Tr)`s014`sKO80Y1q5y3`JX3X zC7gi;iLx{Mntlx>W<5WY1<9vkVRoE|%Ywfr8^$0E2ZAGi=I?gMTY<<}_Z`N_jxSHo zBD1Lkuix~CG!K>G$o1VN?&gL!2wm3E2zO?hT8UJeyJFZq+_#5EQ# zvWVb06)@?w4?3O2n?>}Hr;-ZgyoLNSk!X=K0E%7(Oh#x9DS-TZK}1qu#jI7V=OE}q!V{Q4A9`%8p-+vW;@LrgkwFdRF{g#5fI=nZO#(nLGNBPt z5VHb(_)10-QIwLEQVy}P`7bQE5pe^zmJ$I+bSQ#C8QoG5A_lEN93nFPB1~D`kG|Rv zF^M|LZ~G(NVMrC@g2Kqi=n8xv@X(j$Ej&vj-XiG+6||^$mv_P|NKXG(?jS4S-f-CC zJY&KDVIlL8BoXHzKwPq zUf$@Mt)A|}T~}{!S=%sGRdEE_YsN^Y>wuImJQiJq=lTxsckbQ_zy1>mGnMKQvXH6z zLN$fL4T2c-x9|`xkKHq`UBoeSur9TEkU>in-%B)snB?+O{g)KrNd3cPs6Pl-kTK#I|evTQ&Y2~?Hj^0$ZC+d zDq`lSV3O2EfRKrm^&?`($Q(dWfvQ1)a9Vn<0mB#5u>|U&+bJo<@Wie~o|Q{EqId7ZuS#uR=E< zGz@?d6y*pyBfJp`T#NMO$(3mN`yc=}xqa`u0fie`K`>kAdqdd6kwajn(AiNkL^OoB zf|2LK>>U27n&bFRpWeN{5&oseDLcIwG%fZ&Pw6Z?F|O?hl)UHOdWFKL$J2AUrTtC6 zphsS`^P0SUW##_nw&B-lOR&cv`e-9xN7U@ABt1!x52V8B?D@SZPKb4nSop79v!(`2 z7}F7x+%C(?yQrwhP>_x;ih7L*#d9UotozqX^`0dsZwM)0eYM(X!Ysqh@oix|giZt= zNtEWynRgs5IH$xKg5m!&w5rrmhBBr%*^ba*UfU=?CInjk=^Dvwz~d6 z8(;=zgb?pIQW)|I3g`Y%U7+f2rJ=c9ZPfidqw*Q-02CA|kDSwi)vKk|zU+ zM$Qa;{YoOpQ8>mz*b>t9qT9U(sN)%220f`b248|Esd?}*Y968b>^4Jm?DRk0K;)DU% z=CxI#4N=;qt+5F%)%#AumQTI+e@6q+!!Cq$D66VU{F*AkaViq6B6)NYtwl--N1blA zSQbS<&ICZ3p{tnoCYYmWX)+B_1{y$SB-HX0ckqWIp&dqCXyi6ez)hU`)mDzXCjC{I zpMN)$c!=1509DqFgWeF!$XOnofdD{;7Xc4zMK*$2PUvdj+fMS(#k4hN+d zQb05kytsY$F$?jJAudfT+?q{%1jzNx)w5>nayghA0z?;qTCsJ0Nl1Ray`TWS1EC7E zna;sM*BTo+bpGXw_#xOVFm2cHaM~Yg1%8Bd!$%lb|5iI>$&VmlG&U+nDc^-k06kk? zL&Gm5Bt$qZc)99Z#9A@MxFNct+@N1}0ud?HpVm`)-QRM6{-&bd)^qpI?_9g%^!D9u zD|XdYudvr^y(YW%t@id+yA*bwmer#;Z+&UY*5G~H)@^wxe&*^=Q^t5t&yi*kXUc3U z$t#6XNeZF1bAr?E(vEJ&lGAcmblm;!kZ1q>JtdsX@nx136w2YqpI!(A%W!QSzCz;# zSlu%`%vN4i;!?L&DOnK^t*o?ER$BVrv7J63OwUjvrDi;c`JUqmy9iL<2-mqjR&p1& z+1E>mK}Gg&#=n9OSgWY4aU`q)h8Y)@s2>UtGZT}nx_Wr?Yjc*owp1L_`0(*#5_nGJ zew-si`Nl9@eEg}$rnJ-QC_jJGiQ_n`aT#v8l9ZG$qQ>1;e6Tc+B-bYarY(E`Bi zeoGlt8iP7VIM6vx5xgoHsn}f1vmID{m&pMp9v&soQc&M7$VkNJ{mPX@bK|5sYmlJ= z#)zvOpJ>i^w*632A{huHbNl}NsTlrcEiG#J)&tF%$&g3&XuPP3FPWGmg-gfNm-g5& zadOI4gz+|#E5!FfRh8rQ0Mtt7&fNsm+p%}=^T5Duv2k(C0s^Xm3K|;6;bml+HOV0| zk872;ut=2-=X;8QX5U|P9;nEqE}?q2XEG>R+2_x7*o_I;&9gHz2`^vD0rn~5vy+mO zdjM~80W8>pl1O?TB&+`mT#ISeuGMel<-mJLg<&^~T zWb)<7HPu%}2k|Y?&6rM}RKuFAr=*lMGD^S>h-cNvJ&MilD|k(t28$4glQYkil6##l zUi8D}^km}TkiGbrYgS`fniE@N+Olw<=#e&!>Px*lpun+Ei=(EzC_?UP(=@|LMMK`P zbLU6TClnN^G+x?9Fb{16A`q<9@n1=y&ViM5amht=4fphG7X^j#_G0!|h#KGW_QoZI zyKkbf`oKIp%mDL#rfJCOTgIdMWhurAwLcPhIb z;$uIi|6K&K+!FT}wZl|+5EYen|NfSJA|C2!Ju#?XaujpTwuS3x)qO!S!qwnlsc?Rl z<4hT)!xO+u3P3V@d-9e6A?A>bs>dl0)b)t(IBSR`a$2%r9fAiBNTBK0AZA<#bUO*P z(eWbt=#sy{+TRa3|Mh=*gCinR(8LD8OF6?T)^FTck4zn<$HIE#6dPbSkkf~WYVdP| zNyv8fnl+je%{N8<`WCyf^aq z>p8VgbY|t>Ui@U!;lFL&yE5R2~Mgmxva6|`nozJXclw8f^7CI znR7UZ%57Xjk4~#GpyUw*<*NWGf;mLYSnXMgHgsIIMZ`5&LN*Lh2AeV$N&xkadB38PH_* zuv9Pi=p-U8@sMp6;V1_IC?cr(41@>!4jT6$N}T!laiL-RHjAuQi!5Xi(6KzeH7+|x z9Fcqo>MR8xS2jx6y?c1r^X-5J>!ZKlnwj$=?z78hmKSINtn1-HPrg~X*$C$#Olo58 zz$A*!vF$ZM90MIApf?kV23mfb7>GXgXf*DK#U-VtPOUnsnq`rKaF6{^v*Lzbtikj< zwr@9r^+wv;nKRc(Ij3k9X?kh*;UeX1Y+gddi@mq+WD)`>w7eGKgzMlgI}bpfl0#rR zimLbv6fp8t5>zq_E=WjJ3r)91!<><*xx;6tW&ZCh05#(TiX@r5MpCjCQkfpjN0niB zU<_Jrli<|CIg=xdjHWXqowOV}H$NL>{3@KcaK{JG;tVS-m(deQhh;rB#=uCqV0v{i z64V;V9I2*XxdxDSB;qkWr@?2MOrz>EINMN%-D;0Eip592mjOzAEMT96JjnzK(xmy7 z@mw+85{{c4dhqaJ5`0RGBwrFU;x=zqz#-&#TrYzJ#$Gi-jd7?=OazmGx3UN%P{c6eVu@HnG8vntOU{@znp)GEX_nCUhx!Tvd?Re z#TTT!>tE=KRTV6$8yhD=FL(;r$RaGPiTq6+LTs2ji#}0BlGjS<{<}1<+Lp0Y)H*h` zYXqwb?U@eFn*FI|pO%`cWMB}7)~uRoawKDRx$2zJ*Yu~P^&nPw8az9QKIQU@GgTtX z`JjUdI6+`s8P1Q{6@c?%+&DD>f#D)h7XSmP=JK8zoY%q7j>XMl;^I<3oz&sr{3Jq~ z;$+yq0`V?bnj2idX;TBLo*Ty+^$iS|`T14Qj=z*WV3~wa!_3R8j6hUig+VP!^@s${ zAq7XejY*JJt(t3>h*Ve_lYCqPfW%|?yV8+@&JFXH&94%Lmu7Tl=jM`NRVQf`6(Y~8 z&l5I@BVrndMSZ{E&ekW&GvdrIDN||&sV_Ll6&xP^9B~yBgj4SN`YPadaGTT}<+f}#mJ<_Sr9Ec_lW>x z7h{K7vIa418qRJOib1n6!hyK>)p{l;AVTBwq|KXORYQBuM1V5WxKJ~h<x2wP*e zbywYMb2W(?roz#c$ax1E6gi_7#98)>=jm+A%DF@Ngl#gkbA zw~>~JFcjISlgQ+k>v0-)ytxJdEw7?Nu7!Z}eg%p+z|Fh&?kRbA6yhAmcBI-9Tb`U= ziG3tarVZFvvh( zze&#oaEv4m?s}l~t&<+>J?cK1WTL+6#`A!6VKwzQeIE)O2ofo5}DM^XwrLe8DQfOfCH!$v!GyWh9>BV z5cOG)RCEXc?w6`5klg~YoGn8QWCgH>QJF=Ocm8QNN^vsr995zgkj_3jng3a{R}hhT zGH5}NjNk_%q!ftWN>45j<`J2Bj0*u+`>dAZ61bDf5)yY1HX#k@;90K(cv}KC-M68O zKLfdy@tmuTf@VknzY*wqys2&2u34Y;uX+SMd%5! znnd<B&UorRP;)Lx`TDiX)r06F5o_tfBx%IoMnBiljdQ7jMcavH&K00{~I0>(f+2SB)i zDZwa@3JGZdZLVLp?h8Jf8^YctJTlrY0{JH7Ty;C>Fm8o2~o zi|hwzuz>x*1YLm)C`g2WeGLX57b55yuy7s=xxPj(s9I+(UITvq3d&fDX2G0q|2`OC z${rp|Yz;r#i;4&V1JzE>&sT?*pTsRrbQ8@2mwu>Am%#IJ1JmGUkjuo#h+nNea5uyA z(0?^D3W|gq7)Llp_k=t`!v#60dQkX{bi(S83vik>LwdvJR=e7Zss%2Y0(N}_@(loi zDEIh336BzrC|4SXxe+wV4V8uU;Z zN>%|5qE@Oh9yoA{q&n-Ko?T1+0xF;jg6H~~ssPV1INM5psXU&e?V zS0BeiAIkCGIxn2AGiJ3pgaLX+BZ{dC(JS%}V^K({9vLNeke&NtLo{o!nh7XP92!Y$ z=$#oYp<@Aq$AEd+WEL3(Jg&+p6IlnJ#Q$6$VTF(#mxW|Hw{tT;=6C+{7AW{04uD?^80jF=(b4C5xND&>^zP z;ZFT@n2)ts8^Tn~jw4+?p?WWkYZ=;bL>-JJ0-^(}cmZrql@ujpPlP7xa~$e$?W99<#4c2r@)s<$7J-qji6u(^tnUbzXdeScud?pf(Mu zBnx<#8}LxiIP@ zH>i`h(8cn%OQ29@fA=?+?>-o(_@27oVM1IDZt_r#W2#eY~U zR+LH~`j~2tO)L?zaLmU9(@Vg4EQa0~@Et_v0Y-17>ktBy{TRLTAFkX%alJMV!^zG0 zJX3sy{wmL<41jWl!C5dl!UhP~N52pvWViW+t~UVkJvxz8v=PlO9iO0gk`@A-qLEGu zp-45`>M4xH%9h7C_(3b;kuQw%l|I|P^V8+C+5cTFS=fm(tpO~zg9>}==FLy+ROlW! z;*tRSiwFcnOjSu~kZjNeA_GlKLa=t=v1uy*@E{apQ<%Z3V2D7pJpcx%WPLro1YDhf zRmW94vdg&uZ-EsR7@jmWF~RmpfrKrMRBErgyF}9S=XFQ{ymFhhA(a8v1B{n@Aag+A z@Av*{`M-9d!%%Z9gb@YYNHBjTD8XoE^b*TU(?yw{%O0d5VwXcNsMT<6i-p6b02n&Z zl9dL)Ht}{X-S4R7;>CK*EbRKpo)9f&%pih{@jf^{5r@O|N$~Ljqg#v%@Wdr|oDWhh z@+bhi*+EB_1{iY`BOa#;8=sx`ArQUABJW~~YG%zo$JVFF%pbp;ehLR-gXrxC>Lhqu zt!`YuaYLwpP4$&H<`j;0+vKQc3VY*`9ewZ>`Ln2#N+g9pI| z4RtU;Y`^T4D^C!JNkR&n=!=LSHNXfZBO4Y3;iff-5{F3N1N7FX@ggz^hCpdai5T{4 z4U8B(<|C2tWqdL%pVbo_^G`*|5WEbsd_h{e0gX2e{eW3K44yf0t z0YF(I2;wA<+Mv*Wpj`;4wK%i}T1jUNt?XsXP+$y7R1-&D{BWt@MGT5cO5nI218sR( zy_y8feQS4zTOVnVcGLcJAR8UC3Tqh(S`IP5qsf6?6 z3`ryMysVy(O8ctM0w@v1>4*eDF&I&}{|pi+s|Gx_D>yXNS(MF7`zU}Y2(vQo6cL6C z7RJg!z2z}i;QkW1mrVM$T>GHn&M)nFRtk}3u`n z+Bm<$I$k(to6< zw-?DSO#+)D9KR*v`BS)DBb?}(>$tHQ1~c*l0>+RHTwux{iC7tTrXj+W>aNDd(!%>RNJ>w?R3$wB9Ggl}LnDPKK{y0WixZ~gNnIQF3tqD3BT^L^VsO%5#-y4BdKjzT&TC?=iwh!nST_*`;f)-2U9Jm!Ywf=-KQ=;;r z10MAG0KtJvzbshQv?Ai9GI187mL?dX&Ll(27-&q30^X{}{?eLM$^P;WL)0U*$u05Z z2%=^+cruEN5YDd6;f!4-&NgORwrid+tgM6VY+8V4T%Lz?f<15_x-^b!Kx4*&v%$HE zvVVt6_QUyOwc^;SlW>FkAa^M_IJ^e0u^;P}z#=2CC|;A8es|V0N<&oC3tXuVldg&u z2QkUMBYL1|BP;3QNCE}MAUJYfRJ1|01=bn_yGvl*nK%_g)FjN9S0o||UfTPr8BHES zG651~Siv|? zhtG+MVmeBJtrNbSnmfQ;bz<|TO-edC-&GosovgtTQ2Pq*#)KzNPHE)Y{Vq-;AfAlL z8z}9*33s%&KOVA>fX6~M;2F%rSU6Qsr7i>#R@$ISx-|iRkm;T7p?M%_dG;Tyo{$wm z5?BI!iSKnVYU<0;Z-XB_NZ3poh$<{VMJp@+FO+arfJhkXTsq;mJdeQBY_D6M&UCwSvXDU^*1!U}{ylVXaQ zj}+8JvQYpwdYq%+trJ>pjOVrmc2mAyXm=5r#K8@u^$@th$Z%+gTwGkV$M!MB6GGzM z8Ssb|{^3cTq?6TuL$;^dx_gey&S{26MY+!w@_;p<=QU?rMl$^OWCQ2?nod5MiP>;@!D#wGgKka553?2lFB@ zEiH{aD}kB~I;w)KEO|3<3sRjJnnBR3pwR!J#U{euM9Vmen~Sjtc8U9f6)mEfnc)Wd z3XY6S1!=-t8v`GeefpFznTfATHa9m8T*2UwB9Dd@p6#YyM40>wo>GRTaI91%mNTqj zJWcB)L<$znVk)>(QyJDhSZ*STgXQ*E z@#$r%Dr#z`V#Prw-Iqt_aLUyL4g*qz(9(}$&qQ!5;CnxV(jkP$O298w1mZA!c?&M* zg$sAF3UN56DhK@{7ddlo>+k0(B8AitLI}Z{p_=d-oK8x^bB|OotsAtK=akW`$(BX6 zW;Rq-RW;&CGmw#vhgC3OSiMBCrw1I59pl5Ud%OFU26AG6}gU z0jpks_B zfCf>GQMBZ*@Er*ID?>_M9S_<#;Pc@bi8vs(0Xiq?pBJ6-|poXmjg}4 z5Z#W%M429EKf0C@)Jwx$QM^wNS|dbLPz|Alkz(R^;HILUgM)(PO>g6Hq#Pb`mH^|$ zq1hUF5V%n|idEKc$4pP({mSYSbbG-9J19;-qRmB~MbNd?SwjjJr_@%jU0YsNB|{(q zPP)RLBDfG_!4%sSk(K-PCW=l@+0ZkFXKrfJFigw5IJCfwNJVMj5yEUiEm)K5T@uxP zgEU8cVjR+irc^I*cOAvm@&NE$kXO_cc_P%mLllvbtk426Tz?NyAZcOVma7QeWj&I# zQGet!zTngy5u`|F{r98=I~6$QClDr_WfUU$3>>3CP9>Ng&e$WNUyew@6KMlCc%W`q zhxIIaA#hb1(R%S99RkmzJmwNfusqYGejvXQ&xb1_vIxE|MvyUrX(Sne2R^WU<=PAh z1yn5oq9FEFWEYwOaaGB-1`TTvaPJObpZz%TgaXB`U^p-E0tuq>kxN6a83e!ce4;(a!j#Ivzw0L1 zM*je*DC)HTVOLTN{D0I~I+WSz6)!LsT@_K>HDtlci*t~5uu0kM_Y^gud2{3OXfP>e zS2xP@X2XfkJucUR57&@X-HJgONYYf|-R=_R+jMH_+Jbx@=R~vR7 z`vM)6csd|Rh;R{+7`7x1ieCp%o4^UmG7}-k;i5)74B;5ku^V2#rXOm{Q$}AWp#*{o zAk;;M*t0M*2P21r9OC%PZ=NjwpfhN7G$elUK3ICN)NO@Hww=kGSf&Tlf;B5}A@Ob? z(H<;jC+z{{f{E&UTP5z_S%3&W>od^ofaORc2Q31KGz~8U9Ug!?j#;fhTJIpFXjQ_N z@O0c~n72u&2ojzG7$P_gbQu3J#&Ct(K;{vA2pqjY{OEuLtZ5}QmHYx3cfTS`dSC|( z;$Vy$xSNnOpeLi?NSPA~j&u%!BX!up&~)*C#8SeeU`SiUYzI)qJODThvSYRi2n$OF z)&f8*gD-)+Ji-?eDOI1b*9;8G%y>v&fWHGZH~`dJo2IO?67di@NJ2o==sjd}0efRX zARDm24@OXr%*)fKuR&HJezYjO5)+K?WPEJ`+bJmnYWstm+ztxMD{uOz`%o$we|@*+ zt}Et2F?W}ZR)a^Pr4ySy{?_g#Jl2MgWFm)vt8nAdiNtWki7_9dfB^D|5k`;4lyTvt z6PRUfh5^3oroDVm&_)Q;1jr1GK?Y*C*Hgd?Q#^tmLletMOw*74bZKO|p=&_&2?B-% z*(atc!9CCv2n8Wx0o-S_aPDSKK(+3-OKl(4jLsea_=~6%Rn5H3n^gcp8hA7cGhM ziw;HDIR5ofXc)NJ{X`@}(h46;3?bYB0s;`zz_1K}uN#erzLevhB3?+OLGtW_Hk_J> zuZKQPY+M{vR#a7G#&CpVPTXD+yOCn3^_*DJD!u*jZ<{uC9lpXG9{ow6BOZQf3h|#L zCUpIU7_b^JI|*b3o+MD4Pz5BQ5|JB3aED+IJowt!)CFV^O_7+xP#*|CGlBz;oeVEg z305mv7m$~JBw%at{7B5{37ps?;Yrdt+aa6xO|y}881c&|DL;m1cyka8~A)56l?`V6}fajQnkT@ zXhwhMk5U6tAfpUXdJ>BuaRBT^!Cv$cVBx2*#N{C=g&++AArp5!6Axb@Kz4atWH}mV zlg>kSBfdwbG{grStA9>_1BBmN0#We6M4N|4xtwA-?YZM0AnX6b-g^K=xjy}Z7!U(N zMMQ#tk`x4#C~;I&k_16SvPc#r=d1`E10aLssN}5V97Kg7O3pb+9&#SGU(db&59NG& zYin!k?$(|u3rm@q_X+*<)BWpTcc&jkVu_{BMc~1t!nh@Vp^Q*30Xf0o&j9*{OcWU+ zP>2nnoCR{pBDf2{eo(fsrJXyh9>E$QERg`p09ofvs9{P5*~Uo325e@qMS=GKw;M<> zg4&jDFG}%8$RI>FbSy;jK^Y~1CV^tR%|JRwxMLD%&~Mp59GmSgQT-o02?SXR476!? zgkn5O5Ev$-phyD8WE$|4cJNgZ00X!K(@^xJ3E`Z+RgxUd&K_X0uAjQYuMPl9niUO*EI6(;B>j1?`pQb@3=fEZ4k|LNE z7(cKX0pM^z`~$2QsBpGhW4l>KvOj!KPF8W15axK9j;`GD3RrNUxsbp$*kKSYMbJ!8 zT1Ifd5ljh5>OyoFxY-cA(odZ>yWR@vCJ0J^#IS%j#RFA45v#orqOJ{g&cHi>(IYfH zh~-PjgHl51%y5YzL<)9x86cEk)mni016(XgG(@MtUbJm+%;}k3Tv-WVK=iQ=XAyn1G7{5#xnaqp*5CVBR1)2L$c`n5{sVXZ6PbL4||D^8!K) zD1@3X;C;0v-lqo?b|l*xa&i#-7GP*7xMPA23hFTAaZ#x>=G`6M!JYZOUJ&(y4jdjB zht16OX-Z^^LG`SF=jiAFfdIrnvYP3<_P4d%rUFq-5)n=$>v?NciQJ_?LG1@J2eAE?hGiy--kDhE3PVFE!y!COR^DqlG( zk#O)RY%H{IKm(+Ruz!dsIB$a%cmQXnArZ=T$3amDBS_hV%?$zr7`%`KFystDJHwen z*kA~C6HFgSXOcl+K!}kb3J)rNNdn5!3~?t=(aEZ&C5i~s3n@|n5rT|D5HrMq1vc?* z65-`{aM9voCLlXB1~fTBl7PbvEa4_dV`vmm9s#YR08C7zgl^+CkQ*d81$bhP4DZG( z@L|A$j|1mZ8lut&PRZ@KI@7}RZd(oF;oMLe3V|C*nPtF$aYOuY@MC`#PN%0>PaT)J z@DH3$vU})c#sI0!v7|F)5!0?l;S`kXWx%F@T}N&?@RNHioxc8c3L%U@cnF?m3>M2% z02>j$ns7z|NJuLj3w6jT1l5Evv490d2Js^-7R&V%K@;HuL2wfYBbtMchtCxq4L&u{04fu`pbXPy34t zaKQO}3XZgXuPPi>NH9r+!9>~gLfi#NYEa=E#|T$07>A&08#n$2PQ=mRcCCCRl{El> zSf$7&4e>b3F&w$~&QO0PE3to4Aq4ysNZl0lJpQ7>9XQXo~~g7=AUOi4+>me?pDRz0w{F91gv z3{nIQ0vzcl6cnhk&p@sYxG7=F;aD3X#9ChC;6M(|bZ9EEq>;gH3GN3UlMeO2fz$J19N(V%9f)ZB2ZfgTakW(7m(3m5ypfN%!*8d&Vn zU=BgB>mi#;c0OGW$Uh`)#)2IT+-ZbN3tj;v{}clSVE5tn*gkT+89vC$bKuLE-G2%M z0VII~Qm{U@Zkg)-lRJesIP(v_pA3{SLtsipMe8Kh1MEmo8xR9h7!fNWr1<0)RvTw!?IE1nrNs4}ReaxrdnZwPW(YtO2e=;u73>0Pp}% z!6E+W^*?-s5VAS}w|QV~y%J}FpST2%gg;<);wwk(e|z*p01{!u@_7fgI|O&LZvQ!E zJfIhx+)wYvORW5d1^Iu-8UAO&0p9(V)Q-mE^Pe||x%sJ2I5r{fO z7)E-n7I!j`qK_f*9Ct{Aj*`Yt4-=-lq-ew8sQN1oAMU<=!=>}u?_Ac~4;pr&FD~69 zq~a`+Y4`bwokogyVbK4KH%|zLTjm!Bzu5HGvno(32eP(sjTRxa3f!F<9`sA zGxvVGY~-#k>`e=~QStRR(g;53Zy@l$AIAHC(Smg|IUd|ihsY~ZexDzT-5xn|BopW| z%WG?zyy;B_I)KS`0ppQfE&p9!$?UTNC`<_jrR*{JNCk7GZ%2efNhGvqs0;yp?>Y_r zBLC}!OS(+vN-bz}1rk2RWuiooiX6yu?7>x7gcx~zO3F0)GZ+j{p>@cI<<-^ryga_L z&9)2+Fv@x%K?6zvsGxPA0v*tV>!H|JpOvlcM9I8!#%~!%mulX>MuDXf0_OA>q&!uF z4-yVm?3iWLmRh9C=4A2i&U~594A{rW7pJP`u|wh9jUf`(U`Vz{cpH*XqzJ78wxK=L z+(a5Dje*(YZ!Ym)Q^CXAm3x-SjD?OeEC6`jI?JIE4!i=G0V~wF=vivdE9HSjpk=2j z0}rWqLUx)xZ!!YCKawy?S&w)P6y2bu|K4JrhZ@O=^p;^WA$ZuG4brMsAyf zMMy|Q6bGvTMWH0nDrtd0)(O9EKAgEA=1YSVu3+|o)RG7We#kul2ksqk<;DTr+5ki* z9I(~h$~77w$pNXn*?=30p?Z3GDP(kT2?#ilWt_zAf<>#SNCEXGJ3BjdWC`%nLpw6e zp%yCy2}5QsA1GJ64{44on_qD+c!=HfhBe@a^@2tNCBcoX&zi?>WIg4kOzN1Hc;bDC zsSl8xp>q zqL0O>=bK$ffEE@24=_2h;F&3U`}pWVJ~(j6f@hNO$`yG81VUliKq919AK(op7eTW| zNCOE0oWeXa;UJz;+qaz>$j+4c_1nUA+9#UOF$5EN98XP=yi9Hj3TOBWkq)}{LBRG1 z0YS!3YK3?;D3LA;H6#H$3Peh{6cq`sI0!?wM|VXwehd5(163KF`;AR)5+fkYQvMp9Ya`WT062q3qkKwhW;^5kw7 zIq~ibC^Zj61^xbF`^owFsF_Ka7x*#Y|9HSz(O9J*!i&#@^?^BE1LCSQ($+!M6VHG} zQBfCU89vhpRY;i~1@O$;)Os^!CMS`qE=<4v%}wczl;VXlJJlekGfD@4!2jF@IDU)) z0tr&7=H;=JAVH82X@6%Tm~%la?P0AnU*CIZb;$%M*t{jgStp=&OFh5}OI?jFyx`+t zpzfn(&$B!rO)-NdZVLggVARf}?BwihJ%DzLKDNd5PzMVc7w|H!na_b&fOHPr_|8}A z2T)*be^FZ6v*Ba3U_6$T2p{Nwx@r~>9@u{r6-aBC*~bGilA3wBow5&2IQ<7 zi0&de-bm*WD8%IGvgi*TXEb-FZf`FD33kj#b4vw^4#2XDY+z*Lv$D9LjUg1E@BeD= z=->bq{E&ge$Yh4e_MT(4r;^`jot>Qvc5z!v%~Bj=5XcDOx734W2!zrlI>5Z4ICriZ zfW9Dx5Mf7~(&ab~U0^dHhZ6P-X^vJr_R=PF@Mfn>5Qrqnb+G{3aNu-n3={Fql z78`6!moht`o&@LBt5?l?o14+#=<0(C*y$r+7s_zW$>>u02ASVmohke zd7}M)asmGLjpE-Yg9!Yq4F8wPkT-7F7t%Smhsn#Tfwhxmw=fKy^H?ClCa$O$f!tE)JxK>W(ZKbDCXm&@_V$CU0i;f^ROwv>4G}CkBqb~y+LS@=z$0LN1%da4 zct;z+jfg^ARL6lW4Is<}A{?$SihJ?$;(}aEWO-RKz(x=QSI#%n0-z@nnv0@Fii z3YVclx@S`5C@$S!D@O>e-=T5>)TzCPhVp5;;Jxxgfj!+37(tk<(=aJ%6|^zO0K@>9 zHvWK!#6zVxNS$m1#)>6yi2-q7gGi=*KNNq39ZE24r{$lLO3VybXiogz9RqMxcft zG*cc0xQ8^u+R91?W&pWm7-0W%3JGm{&X)iab^E6nss?6cD#_5q!$X$Or-sCf?vj171K4 z1@s|YmS%~^?fqse0QR6^a4;GWp?Guivdo7mW6*b`{rcbE2O%`{DBu?D*B{FR6f+Kl z5+y62%cQRNU{+9*s~TQk6|S@6($C?nA+-~r zw#n(~T8Ixh-8c|!2=7EtK`1a<4=#9`Im`u6704*zhsFiqf+P6B10bG5qAgN*V=DlU zI{@BL!pPOXLtiQya77oL2uY)D5Kl)KUR!XQ!Wdtn;KDHO@bCNEq#5?eTkelHTgo3gmN9fq454$dbbIGynpe8S} ztpF4vAnoY9CW~fD8NjG8bn^El+ZSr07OST3mci z;zS2HPHlq7N)lvrqa-YVeyb0m;thaB1EAc-#KwZJYdDDu)_rnrt^t+*#Wb<2fwl0yUZ$a$AL4toNx8^<)tlne(>2OBGmto?XzzbJ;j zqF%^Ng4#BN42pMBwzk&&dfryCU{F7JT$0-*QA3C;Ceh}M!Qy@fpXf4tnJ5VS=CX#9S_a#CB}goLjU z;2l{G=jY_`0I$3OBA*;oJ?-s*kRgP$yxMIl*bBR;CH)J#{Quo1T8FruaP?ea>F)aU zjBrtxj{m!QvZIG@;h(ySU-15~AQsetglt0Vm$!^gP5*dp`|Qpc^Tf8~d#bO=se1&< zTPr-fqh6DnsEj=+2tG+#O?LX|HH_yBo1^f=TGhrW@k2*3=%xBaJE-!h-?$MzzvgVi z$v^t3ap#u^pZNo%D*q!!_XmvkM?~-WAE4hK@xMPH!h?SV{QiA39$xgn3l4IK|F4*V zSM=}Ug6sTWl>+DC_`ix2EWCfO4?H}#e=kiq5C4C$Qj8K;@HpBa6DM3gn4 z&%`#h)sLG+X{7Z3={;kRRtP$jm1va-7p{x7TY?;qIh z)s$!KbHz&y0LF|1J;xNGq_oHgvcV)wfIgcW4&=?E)ExkSLZG>pnoXB3^i&szcAW@~ z2C_c{A)}-|KuIGcK0cnCmv+&VV!PlO{J8T+;r4aFFxy$rKYMLT*EzK}PSs!<|9 zaNbG|>WTz-dV1cA5a1CzZ~Xvr{tJ6HcX9K(4G0MboU-xp@o=**#}LmI(q0r;0yym# zN1<)_1tKCMLEnM?eq8ZH#sd~X4p~>CJ421XJkMW~E9Z*b$qI03IGvdDdEL>VtZPFX zXeQut19JkI06O*o3*u}7q&Dzu2QVcrNJEIwgyNV9rKKW>Qw-H^ikF~u0B*asY+H(w zifYLdV*C7!B|x19l!6I(Hkg@*O(T*u1u<&z#j zZ2uk5qyZ>sbD+jM#}y#Sh+u?q@(VNs<@rl9jjUmzp-&+Z^DRY`(!r}5!aMe3K+VZD z=?jHVPy69LzW0D7032Lq31|ybTy=nl2T&n+Mv1_87gAT~dX0>io}M1YA~;VA&<~(H zwyFcYz2ShR zU|4#$1#1RsLV+90yfQsLK}L-ea?VL48^;_>hZ z2^DulU7qDz5K~Z4fL?1^f3w;2A(f5-7%h-8wiwS>VwkrA`Ha<&ZdAN94Y_9tz+Hmg zniBGT3))b@2FikkTQy6-!(oXw=4{KtpyUu6;3LbbwU=I6 z6odoOTL(Blz=OM+R&~JbngV;!(zNET03zG4(cARYZssxaNu!XFg&=LjLf9Mg=6G*e z$1L~}RdK*l&bHhhStsZW7r09(vph>#AJh zU@aLZPYkH-y!j1j5auzrL&Tja+A}cyqz5&?Ug<{8PytjUvFtWX7!yNn-iNYQ?-gW) zc~~E&R_|^%?vApV+DpMgSpw{Vw0*6CDjku4$c+mQY{(#*1!|1z0S6CCGAfkr%$h>; zpau+701O7^3&<28lruJS3AX1Yl4*bP@bbo|r<(+AeF%hc!5=8iD6gb6fs(^J#|Jyl z8XyU6q1F(Yz0V$0Qgz^}$wu*Mw}q*$d2<{aLAl-Vk|f^u6p#UsQU;Li*4{_k!r22~ zX(cS0C78#2aX)>3frJR42NG%t&5XyP=3X7bK!k=7*E5`FjiBXb2(+H7SI#w7PR}2H z{l0dL8u*3wjgI~Pxw*N(tQ)J<#92VGuP~?_zzG}~b@V8Zed@P>Z$nuoxkt6R>CY%F zhykL9C}*V87y^?bas?n=XJ;^9$)q$t^v&P`ZNh+oM8`!ylCDBS=lf7j8oGvXK^iTz z(~B!8;2(f5=M)eqtX+WOB}NOGdme%p+2KOw${-;nB?bFyQ{)N_ibAexePLgN9!+sT ziOS1~lfRs$-{{h%x0eERj@3GcX7Bg7P5eRS`CoV%sUO<^!|4T+{1l-Nq26O1I_Ub+ z)mn5}c3H@8sA-7Mhd5sU6SH%rbJw*@`pTF}3d-{}%ej;MhI119Pr6TC4v@^Dp>;Fg zYs!}AD}u_pE)d*b(Jz#{^I52QMVxoVq^AA6YF2@(W$yAbOdyV}t61A|({ock{k?+Z zW%@Bc!XPh&qzCd6jAN4a6JwKGlv9+=-JPK+{dS7%LaSd?${yf-zqXfZ?C~)DeU|fM zN8VMFx{*HL3BH{&iM1QHxg;jC@K>Q%WI>6und8dpW7`$Z9}yoGe>7+Z$V*B#7Dn`$ zGGmZA47<@ccmD`&|K4tuZ510+K>tkonW3S9gtof&T%Vn(iH3`1sl$MhWyLk}&YeSU zLEd|~QEs=AW6?b7Miv|AgC^oN2j2TFiX%go>v&fvuRbMdoy5^LU#zZ_ET!JZwI*#G z8Z1%oZ{yO(|Cvkdp5VnSriPjWX#_LH_rk8GIrIszky0}0xq332GaCU}`%7h)}X zsE3JXFFuW*1|x~z;Me^{*7*D&04k;lT)sE*i88GpO@Sv z&^ZInqeTUleGwbJWV?R!#Mdt>m90#LUtjzBUNTO_H}8!t^@@+0Eq&BLaQ8Y;B zNy}Fi-^1nCmxmYc{O7CiI>qLC>@@pbYqu=xIWjQW$672f3qhm#%2j0S+v4aEz4Jkp z3Fjjf)l(MBzY`!TedPV#mHu)LWKMr>`yTJAaUFr|_T$opRnyU#0e(R?BDNfwS$>{2 zzOmw%#@Z2K--#+Cm++<gp=!ze+}U` zs!&$WG?bWg9`0B1Jyd?3VGkoN`s9(jM>3O*;QEx53A0s6tFmwE4(+yBO=)Oo$EDeu zjkr&qpGsR1$9v1Q_i0Z*%1cB#aVnPxTn_TLmQ9mddu*$h*Vynjmm-H|{!R)<+r%J- zKwqP(7&%_XvjZw{#h=sP3+lCg)%Il!(u{PPQos~iV`|b;ngv^fJhINlKVWHdC=Sw* zUy7v`82gbruMw4gUL9^)H}kuDc>U!f9WDN9_PQ1$-fbCMTmDfTni1*!{a3bFm=edBmo>FaUA9|C%YPm@PWb5fd7&0!u{Yh~-&$TOSGK^Hu$ zG2L|Ww}?|i#x1sY+%pPNK}?z(lAKz%7B?E1#m)!3<+jrQH2Dhdnqr5|rW~3DMx&<& zHQ^GL&GG~2oSt^Qs%oEKLU(b`%0G@udVr=k=?nayTmTN|%RnnG`1x^keZ;@8PzSz| zknfp9?)gy9CW#!HB}Ue`_YJuXb;eO4AcxJUR?YoGu4vn7#5SMXDuqN->cA~nxMb>wM)4xhZAJw*P`D3ZF%k|G59kx53Ju^bf;xdNDx`- z^o%6x>MrBya(eJEqgQssH+M3mO@uY2=wX6uX9F$X+w*%>9!H8KqjC{%!EA193Tsk^ zEHP?3q)Mzdrt3$^g`Ok1an6H@R?qrTBfgi}6q>u*L+W?JmRiddl49kN*)Z>2=;GAE zLbOqaG|-So=ZgHBn$&6MX=WNo`(%-WKHv=NwVe z1NfG=M8AzH?7Sd)I$a94qUmqgf>zE#%Nus^sM;7~kOMjB(H}&5A-1-*ahkKj|w7@-(lVU^Lkrg>cX|rHz1u}z%=<&95*+Q z&MRRvH12ht4a7|~&@LrV2bLAvJ<)5p2PNy*xO_b((^^{kdn0pX0roy8xc6Ls?=`Pt zTpDK#QbTVK5@0CwXG%xJ&~R^#e@>vOg*%PkxO>a-<0i!25Q_wx$RO3y0i zIY+D?a=X?dH@zofehzh4%wPU8|7z!`K1zy7+5wkSB3hzc>|~zqI9OND$H3|mX!snOV{Yc|{{JG+EB|%*++O3WJ65LyR z1y_TLM#iLsX9Mfy@4CAdn=!x9VMAgw5vr--&+6)+tC!PQqd&0TRlNIkO6o=kX1{ARpR=8E4hJ=yfzQgoInvS5-GF*zL%V|+6;cFWEw3{5?}k;}i%j#;suPkTWVI%oQSb79V@bwWz`o z1^bT^uYO&{!>XmhU9(x>p4up@vM>&8wsRG|Qgbr57;wf^i)WgsFLr8w^F<-o7u@H) zIk|;O4L&q4IBNm|Dp;#H46OTv2&n7vc{(w6|>Gxzilf zjs|H}&U>a#(}yz<=n=47nN*r+^x4VE=E)JBw`aO19_f@xi56OxgJzIzJzmu4y6^%L zO)QPT)6M%K%|eW8D0^3$d3zz4d#eKj-m2x^NxP)@`Hl8F`pddxQtCL3v0{|<87CrD zON5?fbB2zE1x*a^I+_QXYDB_xTfoN4Yj8DUcbL7yKZ50I?)|Z?+GyKnjmgx-;FB{b zsrl6fFVty=@iMCBF^N(8wRV&da@cU>@aBvMhg6L!g}DR>w)gujX;^9?mp*E*5j>bz zxQiRjtc9Eg^a+l88f%5IA1+MN&NaSfW6jjo5j!GwWJzb~8L^nqtn|GMG9WE#lUgEhiq%)3W)F zOW8VK1`Bh1c_Tp|6f&Z1f+?y-tt~Z!LT0(v*25dgEg{F=_E1ualu7;v$~bNwM*XOr zU0Xa5F~A-?JtGSkFxiF@sy#G~OY-M=XFt^$M)`XSQ)Oiu>1yqR zS#blA$bWTplw)@>1WPXwXsR3;pw4P3UUgx^Yj=qRvA!)uExRdus4*v#?K`+ai?8j4rtPU;_K-do5KS= zcfJD^0=jNaO(l1%tVmc|S}ZrUrHS@0_~>jdU!!tts(52DBFZ<8W1esHC@`z@IZ@8) zyVurLhsKpVJD9=8oVt>nhVq#PP3cB80TwR#n_ia_!n4kX^Q?+KV8JNJGVX3fVaQA0 z32mD-cRunKn40!KMk>FXEXvtyZk?Tu!qxGigbIs<}7ci;H6585Kj3LXZ2?3IgmUSQ#o!Tiu`aOj_1zU4E3&W#6 zf*||68yk)OvQ8KI=kjBd41G1fYqb#9F1Jr2Hj`0q8s>%JiPiN-c*U7}W7Oj4nNGi6 zGttF@Mn&7*>$r8Dk?#{4Maz6rEvVk8mhp(dW8S3SP5!dr-}uIXCUH(IBb^GWS-kb6ht`PGmAwPufdALXV}y1+RKQV(>RH3F?Dyw(j?P;Ghj z4WBUk-cBMpc4idL++s2g(;SESM$Qau6zdM(iDRfpn-OnJ(Le-H@n|B89!ScF@NaCD z$+8z-vR@w>ZHbbhaWEhud1PJlJV9q`aP`VSrc;IwxQtX|h!aUjFz`3TWnvH?ZrHBcPmnW#gxqzptwh|IDX>%~tu#A$%MZ)b~Vo zH*^dPNc1lSpbIQh7C=2esPt`gVw#-ot31TSeBMsp!OJ1bV!DRVdv5YEUUBnpo1&?S zT%CSmOs?Bi9K}uF#qAlU^D=0Q)??IUObX%(TfT$FCsSeoa}T&yZ$!R^=sy(n)5LLt zxmyyh-<~?^JTC=+oXc{|lnI@q0q*@qNE0u;QItxUSd@bm2f?Ai0LeW@%MB)(d${Q` z#K;AR%%j6(ZXo>Gp`Pac*2scc%eA?$V-^-$vlz|Y6|SKw#vsrcWwDi3Rt)5t;ZP;a z_G;3DRg=`Zh%hx5d+RO#MpqG7YGHwUstT%zFV}9Y>K|98To@#J04vG3=MJ{RXASbN zsF<1sJ2=KyX3C{jHrQmQD|oJAj#^{|+q#qcjRP8}0x0)1=d*+LB1V?Ub%DI?v@VI7 z+0B(CaDP%B&Tc%CK+9iN&cC|hk4kcJPtU(dao!o@1?mwqxg?9&;Tvu7nz{y72EV2) zzGvFl zwSdmfhNj>OB^sqpz9d;GQXJCbbrLSyBclz1nu{$|Q`_GoM`MgDYtqQ8A#soR}aOubBGW5P9kZoR4fArT5- zHl3RHK`yDgVUPiDaErmqh1QBEb2LXlpvRiy*9IN&Tul5 zx+bp6r0byY7+U@(`V6H3`{Cj1HFq=Fv;-|CLKq=-N7NW0w?RZ+5b#I&1G&qr+J3Wuu9mD3|%e;kunxcpk1zjO%A zpta=n`%s$Er;gubIQ`zV*Os<;vkhD2N=U^w?sB(7oV?1*Co9vKF$dE<$)}TL_VXk# za4;*J-h#9d!;^`Y?}#$m5~+aI2BsXrgOCO3K64(3X3uB-S2}?xuv2yWTff-{D6Vs^BT#cje}97^VBo3Blifx zf}X|4CXNoj$x>dQvmI)QB0fkr-9dmVo0OJQQK_!YkCr={oT6oL>C!oVn=5wp_^Jh* z!CN1^9(S-qbEmsKtfT?0WF7cJzLzU$(Xk<)H$?Yt1e(FnuU2p9bJb%j?xPN=8bnI! zWG@-?PH(%>ZJRIG-OuGVwjaWZ@t*Ma$G*`#Tu;L{K+SNqe@kQC%hip_G(2mtO1Z7g zY&PeUEeEyGbt$jFz%Qx;l*NI}k!}y3{{8fTR&!%)a6LSof@}N2Z*qXn{!2IO=KXKp zd|y^NDyzkD`f>5{*=spm+#+A&H>J;1y^eCWusAIf`OOiiuQ*Cdnq_9deOyW77!_~%>a5xF&$qcsjLC@{NePyp{F^XM z%ICz<+3#;pIO6?23Wj<$Cel&1FIqomJTv$ou2R0-=uLw{*Vsl^v5610Y>*2 zBKdu6vG@j$@o>2L4@FeO)NUQ6XZx2T>DJ92s#0xt>>gk1BQSL!1^Vd*0Uc)-Vbu}e z&+}hpGz4+$UbW*;ccmC>~=on=iR3 zqdlwg*X`p%+3`m-Ryo((^9C`@Lp&K6erf-|m=al&=+C|~AFVr;Uauy_J(E_9j_qA1 z|5J#bWAwDmYZG=)z5#+`Vm z?F&K+x8EgW7FIffS`}zGCa~pN&0SW{-Nn&?r$JZzuAxrU39sESH9ffv^DQilE~d7b zv9p2Hf*7x2_{;jt~ATIrbC~=+?eC;tQvnP50yV29!6dKFWLheOgCZl;FTNg-c4dR;i{%MS96ujZOLd zHI4Nu*O#_sMdgS1o*k#W;j)?)eTVUEt)Z%Pre~%d1+$k7I`rPnkLCPuWIgvESsjB* z1}mV-mC6L{QVS?Fa2D4s7>+tStrgv5AM$bKYpCTabCY#C2nR)}ghgCL&DHtcxmS^{ ztdo)cvSt%&15(_@K6#qfTtsi^)(_lF!qoFs`npnQ$M;$($PN1CwWYZ8?KFvL?Sf}D z6`mV#Hb6cg@!;UkkQnawY(8sBXzn#aSMlGskd01J5zFU#h*<{II39+Bdx}71mOU~>mgZ0W-7tKxUTpcb+B(GTM zAeir4oxLd@pOfQOIc(lp%rEZWYpV%+CwJ+#wjup1gBKw9ow*j~B~|Fy0@BF&1AlBG zcgd?)bXY&k4QFBFJ_p>Ax3`=;luN``b41%uom3LWPJA+@-ENpKr`>77cc;Zeb*>#M z&0BLUHvU$-UN2n+?}jFAuj}p=>UDI`4a3X5j`MGGdEWCL9`Y>} z&AR%M!7yq6$-@)E;yL{kHCyZB*xnA|!fN79Y=1Y!bJx!||4G$4Ur1|Gc)9bDf@MXP zAc5e<*PW>7OY&a{GH`ThiXN>`)C&98MBt`qYEr&FlbrG*IiQNh9fyNH%7OUxw9j^) z{Wp)bdNn=oW$JXuWn25NDos0S7P7;lG%lBFS(De6RAV%mtyUDV6(qMrEAbl}bhw=6 zo;No24>a^}I0}~K;yR9cotwE24kFgyS24C3TNicjj9}AkE2K0I4w0AYa{Jd~ znMrn!4fL)^*SxM--=-3gy%-u?sl-`!`WT4x>(|QHubg=SVryqQUxu1^MifVMb3JAN z>&0-{_8&|=a^9jZ@U1B;R31tsaRQ z9>P3Arz@xv`jRM6mX#B*NHkk^{;6fHUe)Mnb+ALR#r*Nm=&$sr3#vV>C;=4vkb1>n z=TXk_qm&}wKo|n2mdgN(D0WDQJy};>!VPI zQ!A9naqWvQn47%iJ^e?@ALzZ_BJQj5XO3c!3gjBm|4BQoufHbaLqao=K0P<=ZPb5# zjbr@ueU;-z9bbkjZ=Q@zPcN@bFQv>i^#W__dvB;hC~N33uP@Y7f?vmV!%mz-Mse;> zQ?u~4$1SrqMY9fdY&_ph2@E$?Db6}L*bOf1cqTj=)W-FwouJ0dk*~y=I+uNe6habX zvlHLD+P0OA#Iu@Qq>yUZc~fxv{rki7lfrA|3nSRfATql_Bh3>e!iNQI4$nIh!zf<8 zyqLX`LuO|#(JZgE{)e$Jd7A7E{?JP{Rl3t5dJC^evA(-UzkS1&uHC%!b+V~tJBoRi zM6k$q(ND?cWk+_g=WT|Y7X#^NUbQ^vzpXBDp^f~6tob$L-lLj3EO03bL{vIDUIWYK zU4#Abv1%PU>PQpr$cqTIWB6%kCBv)z zAs&su>dCe9g}y;-t`ucknFDc29}P{sH1J-(e%zK!ceuHq*xg-DQL+5Fk|xos+wU0o z?N2{U4gU4OA-PWE4CuFro%rMQEq|PzJZ6D!+k0SVr{zk6-jEmSWm8l13O%(R3)i=~ zxjt%&>tCKJ4cygM9(lvLc1uq6M2eEAsw(mPtkvmP(UEaww5#)thEkUHTz+ydb4zm% zaW2G#tA!aI8&?j~`c0iQ zGcpCdfYbcp!-4+AvqxoZt0oSS+_2??%jw7M1L4#Hn3jY{z3I%fRw`p{_SxGb&&wzRgi*et^^uv7T|LD=}s@DRH& z{z(5u12ykV9~A>ddJ(atB;Gk{+R+7n->l@PWGTrHPZ8VK{w(9=KPG5Xo>vxOsa)kj zMuuMz7V;96tm5t&$c5NJElV5)e{M%?0R?Vi_ob}M=|GMsy@jubXS(2;FQ3*Rz%bxd zl2*>lbYZ4y+ETA*@~??<++bt-^pq?+uky1tKFwL*%JKRiZ2^|++Rs*0nnSX|n30#+ zFIu-=zZvSA_v|tCk~0YX#w>ee$oKo*{B4WB?qbkm;9(0K5im$H(6XPjI);u*%0Jhh zK~f`6)ZH7$?Ye7zfYL_#5Wna3lbK!TU_q`Ma#gz4Gg`; z*bLKdHrCpQ@@Lqe*gXku(N6fKlsor}z+o%fN-vSadHu)T-T95Hbp|`HU3WT{Yy5ob zDIRzgWdbF^|O-+T}b#fFVi+R>qsO+3AdgWnh>-bC!P zK<(RmPN23Z2nox#21s7rCJt)|N8BDBqv!&PTNm(rh^fccf0zdbu_YuG8=4Sk4qiN! zzhkq$81x}7uDr6r6Xiqe)so6i=6xl4o5Xf)kTPTsSJZ!j?@ z^kwFDkAv8m>=V2Cn0rUMd$a~b?COo8)7h(}35X99ks5V?eN>QOV>8b{A)Oijw7!?9 zq&l|6Y$C#Jsosop;IxnUVNmVe-E{R(Hf}bsJ^7)$;XiADP%(G+o6p4<4yxweGBhL( zi;o{vDm%`?+MeeAXr@=e(P0(FuB=$_v_Vh9_@W-(aqD*ki53^!YFZcN8?RbChOV0pt)CQq(_u&t6$a5ZV*(Ac1({4$kkI9^9r8(Vn zn2n6hl5hFqa!BJ17W}o|LlF`7G>g61s_N?O+G(k&%RXdW*RP3dCUZ2tkwga`+~=b$ zU83=tPIn*JbCJA@sIZq}u2GJ7BR`mE=7uj|4N0{`8k82q2lnf#nQRwHDQt4~5m zBC4Qp63_lSu7Bs`i!t5W%WNzWJI~1rz^W(}=`5qo>=Gir#6j|fRzcw=9)o|u&qcFK z_u!UxA8|*N8oBPDO29BORvx>OQ5m&Ek)7B0cmysO!^>*s__r@k(70^2wt%I@o`T7_ zb-OXg+UVrwb&JEEo{QJ%sEH5q2Lya_*WN4-9}5sIJ`#% zr;}6MZ2~91&<-7~52z>fCg}nTqcHKO6A9gKHzgQg5d!!GBwqyk53sTEn^4kvfz{Ia z$$Z3Kc6Pc?e@X1X)2D+iQJ%LCN=hyYjT*0OubEWquorSu9|v>i>)<+F!d+QEMybE# zBFSO=dc1#nb@l$UJr_Q-fNlmOZH(h zgi(*poZjhhODNoF=_M>ayu4DuS9WZz|Ae--J++($%}a}07di`;K1zwc1k_F6sPf@z zWVcjRh|jhsjNW1Y>faO~0=qFF;O08LzOM-7OH{5g|NIaDI`NzeYWHpN{mgW1ywq=j zFRu{wVt31RXn9hIM7iiJ+(w_P;?-6BQ?+_tKbx8DlX7$wgl5W!xSr+Oe=;6hoNmwX zQYt>!o>ptFAV4H&bAx-c7+duLCwecQx$9A$`6@i7ruIV|K4?BJ{a<@AvQU*!rcoT8 zLY1MXWAU<2xQHTz8ng5f6#Nx|fkS`#*LPkW?seu{UOn>MJ>1F~Kk4P-BHd#wwbv%e zwU7`U?UEtiTknJ5ocyRk+pcTZhth2?jQY2*d%vX5ewde;`;^T$!tO2HRB(3cm%hM5 zYCtLe=EKL@%PZmssq?xM71>mLJ#5^2?&XQd5xId2$Z9FOj?EAkd<`dZ4ZjYC=DYfF z^Xg>9iV4eQ1DRuJGF{e3npu$vj!}AMPFHsx|>~_;@<}Tn#B|BVK6xC z)#T9G`!8FEQ@UB$4p$UY%mkC<&Ll#9efV<7S7(2~fCfY;r206BmLs zXxpqz@sr77N#% z`>~1TfRenCuq!3_Gd^$}E~b9RA>5W$pFsXfI|Yr|`c*&<+taWa-NHT*_VF7r4cIDU zerJJ8v*&0UmfWnT=_rZ1Rla|ZSJzOI7rRqDtcFBB8uu$&V(EK_rD?rLDhGDX6B2(B z6FJz{#wCsR(2}lhXH;KuiLl?BQe{>xi8EHJ>3Nqcy)m`b?P4xb3Km+n9FvgS! zNJNf?+>7)w?mGPv1@%~M3>81VPQFbR;~x`#PQY&hAFlU+ebyGg)gay(^2*m_au3fs zdFVS3=-cvz3*ZwG-Ml!&FF+tTNinIVu*3AkuXBc|^y{-uyp@$t+G0NrqJz>@Es0%k zSKg)9GovTliZ; z{<~45WkekX&ybU!!~LA|#JPZ7vh;-(cG)U?^0DrQBv{tRJZ^cAq*>-ZbI&U~9~!zS zL`UuEO{JxC7{X^Z_JHn#2`L;SY_9`XX z?evAP`pmUf4V+%bz^5b^QqxCEM_#{qeS-E;qvi4?r;S=Ug+oxnqv`<6VaV5qxLT*d z!&alZYuvY?qG6i=Zd%Fxc7h+6|9wRl0$2v$;aq-By%^Wy#2hYiv{~}dba}q!G%p-Z z$^VTgsIMHLqhqH+a|%{ctptv`I*m|W<%dTZwcijT78b71w?9R;aQyYfJA^(Y=uno? zpu3>x_km2I^sdWdW_{M!@}aakI2h$cVWZ$nfM z(!H#ddl)!zpv(9q?&svt4T;xf^V`QT251t^C9Trkx%nlJ>9QN@5`C!+sY@QWu;Y9L zvusce%KQfRafq%ftka)4em^3WiTXGdKm-w0`ws{O1T$IqXCtN0!}I(iL#hq2godQ0E>uC!@SE}d6P z`&p+bzeiULaNte*GrRK!y-Ac1A;q0T5C@0A{aVQ)cOxd2q4Ci7@8Hxr)P5mk7_v^$ z5VO3ql-iIunWjOM^6;kNWkQlhGfRfk)bC_Om6Wg{8ea>rUI>mn@mIqd-tVK7c+=GS zK&}@mY(HKfSvN2Ar`Q}()=;#?|7>RbaH4hj$+h*>Jit_sy48taITfeP@VT^kn!ob_e1r)mVKAS#i8odhNNDo4}Bm^ zN(ziKhy>$Y9+hstkTQDx>kFgyf8ohD6$vQy!3*^CX2XZidn+v8{_r{5&+L*A)yQQM zQc@6SF@GtEV-WaLkcGH7EMhx?)jH7ZZc6<=-}>kGj>sp`U3nK|MJXVNIk=;HjmiHG z%!SCc&Oeve;OPqz*Xx&bLj2HZ{V>$#CVOFaVScC?f&)%E;Z}lvKjxu_`uY$a1DLV) zG_cx^f(mgG-&1On*bpt+IQ6zh-P|18)`rh4Gy1upfZ_&M2tLO9671UT&2s+^_ZeMdi?<&ZKDn)C#zxyXD^X3gw^u&Kebu= zv6ac_m6$Oum;=M0W=TXXc=oVkW)}qws3y4fEOc~6U(^maT_0Pp$kgE%wkeE;ki;9W z{hMXBio-QG3y}nezF4(6GWGOe8n2K1Yywn(=Npd>rWw^AwOfvky~FqqcKzMT%8Iq(Fq99CN77}75knsj&qTI# zMw)Be*P|fCvOr(bo zKYh9=6rDzN`qrTmR-3~^B$?q7>ctmsgIe0J#}6r~opKsWOY_Fqy|0)$%`!~(o-Clg z+qh<+91nu(Kbj5zs%>q})#=2${n^#^Bre}AbeIwWizbdW{)76MZ28fKPfBV}^P~Oy z?JISYH5XY?tB2D9pQ^gh83jr{mPcgNxY z4<>q}5;>+<_Blb82!y4Na{v5Uh<9yGRFhWw{&fwZJ7AMy3@qC9TkGz`d~y+PZ7mli zxhWv*UazQl(?Q3Hy1R!XKNU_tA;qS`jt9vV36(SZz3S&fLxYaW$~0k7$Bw-1P-+RI zh)+#?t5b)qiW^?61w5U`$;`8!*6%1cpD3q&lVtFe4i5+tR}z;83G09Jjap!a6S`7g z$MZW%%1SjUyP|NGBj)-;p=mA_RLVmzLI5*kq~XeR-~kggU7cJ_-aqxgW8M zk=k=$OBe_!(Vxvd!<5pFhoYbZMwceql@ab|1+_{Dk$rge;l%`;DW`w%_&$Sr3I&{y z`1C6wVvq$Y;%l99cg7!kW`5*6-Q+~vtOnUfjouJxzJKZ^3g{`{UX!am1PH%=ZknRRWkOl!oN*WZUyHOe`Nol0J zk?u>U64G%==}XrI{`4;pgxIXP>jzUTdzo=0qG(f9I@DQF1@9D}Zub zvTCaDPqonyp*LL?(G?742bJ3CY5|*DzM$7HaS$RVP-cMllX+*xsr?au-`frvLPQ|> zE0~zi|7NBXA-Z?ZeCOP**R;1-OJ%uxBWo!S5fi6TECV<4t;md zt^E-=uTXo?uqa+eS2O>;t;|%#Q2+`J8amX;qM~%EjE#i>8V~b)*YUu2OaWDY4cqy} zQaj=s?t!$^@)YIkI0J&!CO+_2?!*SpbdX7+4{E)A3)n}aQu|sqKj8R+a66WU9Uk-m zz~OsfZD|$YN+}{@_&WeX1%9=_ZX5t~{k?x0D!6-1zp|Wb3Fk&I2mAiIyJ8A*%)RZh(lltdB}oKL z?S;uF*FME16B@r+n-Pw_nCs*$rqLeithVIM~eZAKhJ~pNK+ip(aJcWtDI)bc#&Uj^hh2n3FK>k z<{DLild$wl7n;MF3hhp#mdp885w$Rgo@f~ez&pEQSC#dbMpAUl;51-}90H{ZH1b)H zq5Ywo>Lk(Rmq&{4A9qcSYe69ZC8};pl4N9J0<+`8ZeB7nDA00Y!aq@|YCbR<)IJ&J zRvBNWbv%3R>Fedm1_7Lv7z;<~+>Wh;hR4>7@aoXZ+=7XowM_g7b2gAMJ>G4e|`f*qIp}>*f>9&!0bYG@P1%Rw?1z zTfFE0_|XXRq^u-nKc#guv4Y~;^7=*!^#TWIBq&;m?Z95C{1+_{^bNhP%dx@2&_~PJ~2((Z}#a)Lf<&<0&kLn($e7%LVqrHc7VA( z0U$N`BJ~3Pv+Vhb-cb*oF_bJWq+dAsRn^KGXAo1mKQh`oS`5Bw9*6ngj&lsgAPv9W`;4zDLc zO${Dxh1}qJB#Pmz02!sf9~xZ@fYy|g4K1-nL}*hb_6q?0M>#X_pa9%_bT&LmQoVo( zsC1?{zcDd+_=xwWmE@ndvkkJQ%)1@D7jGMSdNRs5^KrGClhS0}EpN1FOPdHX)r6ec z&e1=7aG0AKz1zo-B0_9gTqJt-l9?zow+=kIey}B3T46mv4P(#)a3d`yy@2-WIxzMe z*&z7yX~|=aPQzqhO<)V2o< zTxHa`2By35VQx=C(!^~K87yZU_Ye!~RGIYeg=H{TXLMHKNz5)N2mwzHXkSo!Z@72| z;dw40>j5huK#(p2^BouH1us7XpP=E>raylb`LETEe-OIQS zo;2(THCP%Htp*17Z-n*-@ALPOt7{bVgz9Cs6 zcMr7OK7FEv14fw8dF?!CAaDRY@u6b;eO~3Sa?vEAz7QH4w*lRAV7Sx1v_uOOKny)S zQ+8)-HD11yR#Y6Y9Ay6U-KsVmpM;cM>rhjq6W$2%J15s$d$x8u`wvK#b(Zw=&{#h?(#QA=MG0j}8&z~b0`_xmJ|fWUJGf{e^eU*Iu$`}Q9^8+KvIOMEb?W4m1f`l9!7 zH_BO3fls=LNxA)_d6Q<)L3{uC!@8&bPy}f7?C_iqyMV_&te{|sXifZ_rFa=62B^Pk zQTc|T`BBlw4Jesal64FgPnm__ckbf`0U_S(s;U^^p6d_^ti~sRSjbTKqd(qx`DhY< zlODsXQ`+;WswjMbTV&Gbm*l)XmhZ^m0`X5cS);0`NetZwprt*LkZ~euhkA|L?0bL> z-y`X*|DJ&)LJhyn5OnY>3M%R!=tWo45>eg&SL!7{8aOS`&jn*HpIyaNL{d?gt`=`4 zY`nI0v8dJmd<+&DWDh=tU;zBLJvSqR7OrN17jjSBOZ@4P?C5%A06mFc9BW1c`RP8M zH{RpN_EW9^#$N3MZ{m;?^Svj0lsPKK1V2C+UI8gxKrmM;Z9dg$ zxtiZU1ZNhI#Cg1@!5iDrjVXzrz_!)y9;P;My zMFk~Dyk13z?jSVNT5l#+&@DBnKiGN?;(!#Z6O*u?&K;^%K%pM$%mS8MO>L@y{9PZm1YnORvM#$nzh@bU2hsxn@s z5d^iNu~9y63ZtBt;Jn{1uiXArhv@v zmfX&Yorw4+=!b&_PidX?@cQ^%Vv=tNh8&}Vr4L9QU5|fm2>Nsa;zI>uY@#}rnDWMT zTX(Vl{9FiW-}|hw9)36g6q$0qe~$z5T)t?r9H35v5#v6SL2-0!lf31H!#7|7oNYz= z{ELKtF2_2+o`9(z%;pA%Phi+^1w7;ikxSmJ6moIU0t${JX5FyV90~`gIHxzhW?3Mp z1wMbapK=s{|D1jR9~hrz^Ox%E;0AT`(<20+qBGhNU^#5c;|U!6%z;56(#w}G!9d0& zLMbZb*Dp=uim763mN$>VutFA1K;s_f-CrU1;A;jQL6X>!lDO%YM3mwpiyHs@B^mCX zocx%%yq#{`=PKyG+F#ih9ve9AuWWSG(t1+JOrOa}zLTj&I6gH%tZ019eG{EPw!+DM znJ<6*lgxyTJ3ir^Qh7!Qks6yEr|)s4rA^h?h}(_OT>=#6Y0N7(w;}#2-ZQUZm&pln zQ4gOz8&=Y5Uyd+zZkBqHKZ z11Q_ScGJ$ghG~9ES08;Q!H=RYdjrLTaKT)~fT)w9HVG1L5VCC1rAElHXF=?|v(=_L zXl4V#?jjsj-}?axM|BSoNe5ssK6u;KxZhFcjS?O{uUi}Z*X0XE)b-Dh9@qqsYwF7g2}qm#N>^P=-R&#NLx^R>&7N?WOO zm8%2^hlj1ZvbC@ai|BX>eV9;^pp?+4r@S`WW}LPo1OgVDcXq^xOl z8B8+EE6G#&-snl`RXy*^{?O$1C{;!1REtc~dt^%3VTZQ&M@Fha>tC-yuw(1G`MdX( zjgr+OaQyHYXk;H!o!VY_^FC_QG>+U=W>EajU(oMgDX75dXKSR6xYXH#N{~ z?|_$iBx}t<%%?$9!ZeUBqozYaQZ66K<0+(+WV#`&!%pVEZ0sSpMa=5FFShHjhvCzy zaWKrH1)g)0AEu8d{GbQ8T%zd#S4CIn634}$WSf@6Wb1~I%$nkFq?=N?7^-4ML6V*l zpvNwB*n3JNC{EQK5g;i+_NeJS(}A049jp_x=|nUmv!mq&UQk9(SBtG6b|XMYmhG-; zKbqQ)T$lD3GAVgVh$=^?;`pIP#m5J3{LZo?3%pJ#nxE$Q`{peC-VtqWwQYYtJ9iS% z6}AIq6UeMAM|G*jU$p~s5Vwbqk^NVedR z&fS(2VB8$hxbE^Fl5#@xC_bF)(+4_yh;EC)04+VblK|Qviy6Uz83*ivN*mlDuREle zyY*(KQ)Rnz7)6@XPx12zAuC27XTzaK)9v^3#`Z9ylRxBr%v1K$Q2j3HEF`i#!1&iT zroVke9x$WhaiK~3qdR0`;!9#*w<$k+2+8yH@SSRroFg|eF4NwpN|b!)qoYe%krNAX!IGgh2IRt781NkcA%h6Gs{>}R#^2V{A!dI}_#g0BEn$=Iy@~-O- z>W)+Z!Il!25*KarNyFGvv4p<<_&b*2rzT4n$jn#IeZrz!zQmasWM5o6qjzprOR6YV z`OySc>^mgorfOa6@D`(By>r{;_xv!qT#ygI@EYsyJ=!EY+jt7IxkU(yU;6XC2u6oM4k~{iT<*vLa55BBKk~R~OOpT8+P2X!r}` zVgj+J32)9lA8x*ZMp6xl2Iq}mJd@6@70HM701Je ztNf!?Qva)q>IR-hswCKqMPM@qQ*N;hwCJm-2GPKgC~kKx!3$b>{T0ns9KOsS*>ZPA#S>aj(85COVg!j52@*9iWgTh*KB=!1jMESv z`ip$m-1J;qTXLKcj&Pm3X%V8Won2VEXg=FfF1R{doWIDT`}J*@hMvATp@U|W6>uMJ zFCynpOxln{Ie#)H3$#DOYfrzqCnICKnFCARpR$my-t~cJrP9=IJth-7 zUy}T)$&F1WGT!pWyM7+UbWiX6tQ8uR5zs`{rWYUZq3w{aBY9Snlt*UAKnuD z=s?)ZL&PWh-|v|E`7`%aQv#sO8t~d6;7J>Rd)R%Zf5VSOW2yJyuJxm`X7eDey#}m!jsTk5Dcq31-ypeU z%jvtoPDs!8Q!`^RKQuBY;y}Tzj;Nfv+r$!PKD@ACNWFs2>{Kn^AgFG$Dga$k}|)=OQ#UpNcm( z{EcK%GPE5H4AvSgOM_r=J~KH(1V=&-*a_G5rJJ{oed3V$1@~VZWKwe8_ht!msf0d5`1{c_ZH!3hbHGCuyDpDxyOw=^$EoURscn z(EasN*}nrDy5eVxsw!I9S(}5m#Ks2O`~ilH5!$n>@Rgk`4m!?+$%`(9uZcWe3-{go z2+E5!Rr>or-9g^r`?)nCWP9Hc?V#RsTxN^t=05&r&J5L!R*mHYAhWtQ@!DW*GcTQy z61U1>LxtL7hg-8mX9A!9vtw|-g3zrem<6pG2|OCEdPY`K<5{0d);HicYwgz;b0+d+ zRH>#ux0p@nK-zUr7|>I}X(e=FDw;BygN^+8^OB8^-0;-!QthZ_N&%B5`6IgbOz8tKY6Ru{bZVFA0$=E-Aa!S8f%sBN1+ z#;M>$^dqEu;!oiml1@<~>Y9Z|n221wXqO%9W?4h?lRM!H&RXb=L~(1cuhW+Hl4R;4lJ)iVjRr9gRWV%2YnEayqagOZmd5aT{>QAl)xnE+llmWAdXcv1o#01fK8FJr zt)@;V@5NN`yuZ@4&Z@RiwQU^Y+oHi5;f?#(*0=g+cU;=M;TJvWzffR;7t@vPs$SpI zHNBr+v&oIj-y4}SSDghw-iUZX*_;0LCb90pMt9U}Xt58O6kTucZ@5&BqFeLn zWtTuQ*PR;}npOkR$8WQ^KI6|nOd!s-ukT%E5D-t*u*iq94QvQ)oPtpj)fFTMfPcWz zIuKX_;o}A!xHszoZ*9+`4sOI1iEo4V%b*u)vHbiSBz+3kXm@tqU+r#+JpqTIOUh;V1A zNn5f;$fHKzM~zZ+5?>?1AlG_cqA4ox8E!(|^*y~izG<{~Tt0pj1)A8&1DhRYb+#1N zdV$wd0iQOmNTWOkMC_@3QsU{Z-zDAfr|2)HajSSljM+XmNMSvcpw= z=r{`^GgSNz7&xvlLm&a(23)}I1a}!DLd!co1x-!OMl5*d*`iN6!l6vh@uv*XFAuL> za1TYJ@%#edx9+e9Rg+TypNV;G;1vg)>c0B=-t`8L19rX=siCR)901lfi!FL~UBrXQ zf{_5Xba|IL>X4A@CHP~{fmLKZD?+0Gf<-fgCaG5}rad>)J z`(W}dr67$Luf~;fSGAIH0olPz&oW&$;)iMQj+HX^>(G%$D=&X_UmO`2GZYK0Ffy`G zM9~^`gA$Hm(BCUv;r=bW-j+v6(E)2#w`Sklda~}#hFms5r#d$h_#q(aaB=P2ui5wF zps|P#GKsLaU0bYOZn;vqnL1~jRp5cu!_VhhnnmJWQ}vrvIK6Arjf5d&ueb^wZp=Ra z_1+&FQsW`WW5)NwMA~=?x8mPF?jQz{;!;p}_lK;t^(4{bH`d#lz&w7}DGW^0Mf}>S z7jtCJ&Uq?>vNI>2#1#IGRqmA{F$?d+CO@L88v|7xuo6dz%bx=~KUFicN0L|5Bl$%| zCR^hL*i<6b58vNwt7HTIWzrTFEI@evZa_f5U;?+_R|D@vAXx6j0zX&|<>UcY_Mqh< zgk(OL(5~uzNSKtAB&VpDRa_iaS;+$graL33L`8~KHnqWE; z8Q)w+=Q%qp$+<(`Wr~%1b9a!s&mN3W^(?lpF82xPIPw2-|H+)q?vF-O{hLO~e)|Fg z^YgL?iiERx#3SQkt!Ce_9qdt_(Nq6tgPmXRGFF&|X+3_w5$jG#oEdn z&pN`~TMw)NRjZ8yhog4_CXGD|L#un%42>N$J@M27Wi6+ysOC63Kgt6BT6j6t4g05V z^FaNhvdq)R`GRq(OLx#`r+t`39OEe=w2VI0^g!Y| zHViuLFGlw`iB(P;B%Q&>&k@xsrEs*aO>^AYf=A@ejwOh~S+bGlzQ0mYlS-rbY?A*Eis?cH-oZtbm11OUQ`-W=@Xg1AI^Fs!v*LqO8)$2p8 zF}?~Ow#(HsI!Vdfk3A}hEClAh*@+Amj4qNY*#sV5DR!OCdM7T2C8`p}Q*Ijs;zzOb z?a}Xe6ojZ5Q_u+`f)cCTaBVzKQ6cuIw%e=Qu=MVL3 zq=7~|-r%uD!#{_nYOw|ORK5N5ZD6efYWqcwVa9V05$Ozo{U@+JFxDm+8X5|t5{<8S zScL3apM8BHBCi;lOsY@zL|NHDuXKV(tFNw=Xj*4>maZ)ovx1 zLDSbGl;UG*`t6uD8&<9gPK9ARS(=xClKW-e@h-*9XFHM#t+1`F_j;ufS82s6!Udx1 zTF==G`qc2?sVIICJ?N+h%a06EdaHTlwON$L7$E8G#viyx*uA5Q11TfqBr_pf_whjs zoSsBcT}=%#^If;0kqq%fOz|W0Y=tN-r^=ffLlFqdi+D5qNT!0qLNKDCJpU#lI9LvC z=EOUvy}?Ph@!y}R-ni}$rvQH^=fTJ4>bmra8%Sc+E&1{jk<{!s?6eBDsyeVKeUo@H zv>b_{O;S{2m1RAg!cnZ%pr9BUlad0pT%cS%nVbZ_$!wup{U@ZXq@=0SVNo^;EosGP zSj0obgQ>S1^$RH~rI)b#kxWQvy0zYJS#J1IrLl4h1^Mq58;<;R9<{umc#Lo#M2=`Y z9#wq6ZQR+OvaIMSLDO#drMtU({!YZ3r(vU`qnzO*0|Qw#&Lem|-QCYYM|OI8+DhWA zk12hyqK7)vA}Jvk2-;P-p3Q#+)e5J6+0~LH%jQc80oRMw7`^TY9EWxkjPCFc&zL@I z-CcpG+H$-Jbb|;!INQC$=6(2V)YD>6%o~7UBI{QT{M})n+Wl}YkL68vrtCcFuBvq( z#~F8hCMF^x`jVc$Sg|>764~|L9H*PL%ytldk z@&fEAcg`{YS4HG~{q|#dkp_*Kpnfre@EPsSFv7i=y1G7CQ?Bp9@%-v)t1a%E-&>{@P(tFqQnMGfDzI^ovVl7S)di~8j5(G1lY?QuXk|67$a-rM@Hwk4}C0HLx9|8YDUQG=jI3KJ7&j~uP@&lDqHC7a5&8Ou1&1clW|9B~Y zRR0@DJ3wY%G$6^j>6*J~xX^U}!2_25e)@ZU=G#m?%Umw_o|S>QMXGO=-Ti&o(*4Y| zl{gZ|bJ`<0-&=xLnpTuTL2+~D4axHe|72@0m2XgY>+Sj*6c$q-f}vc!IICaQan$G4 zWi{B8;w780LW%w=|28Fl=7Y4x?+L98SHjFjU5RqsxNI_6{49;C7zR-IX_Z`Eb$nAX znv-+v%&aHn-6u?`xNBh0ZVA2u1RiG(m;sef}(g>ka^5 zBy5bwoPb2a%?W1$FB(7vusF`u?><_>{lWB7&a5utc>n<6{&8iK78KY)ZH3V90rdJq z`br_hiLXnCd4$Hl!YinGiCw&zf+RrxwVlw8ctW~cxAi*Ixz;{&%pyo~!HZPDhS5cj zL;vencAQtKI%OcsQUY1lV48R`sevbc-kAJii&sdO@y=X*3`n;CO$Y>Q1TzSmoG<_3 zmf1NBicKQ{R~(_S>%^x7UyYIi*nSTq#iGI2p`r;DF524K8cEMkJMtHaY}8T&FjK*+moe3+$~)mBME7@ z;B-OXUt&sJVS@%G2H`h@R)8~Ndl)j`)2;bJL6HXw3YOzEuRcSf@r2z0PndfV5LgoU zEC_&Mj}eIAfC>T_W_1VM6p8#FG-byhkG=<+p{s}HihHPL=xV7#)@V~Fp17^D(vgG4 z1NC)e`cr*c!dmD~im`6rc7XS6?SHrc0fZ_a;hyI!G`lK5E}fTh;M=W+-Z`iK7|6+SK8wszY|KD{e5^1r>c(!o>VaQ;k=yZhdwrfIF#5!+8ly;;;PF47 z7(M-)k$piHHl;7|@iY5%f$s>}L&yR$D8tyd;6HU;o4=$2zoBwt6n{ub3K@1sxsmgE z7R&d>qo7|KA;HHIrKi+OVZ6g&IEFJgf>0Q0WB&3lMMXr@ zhZBBtDhMpgteNQrNmV4N7CZ^5eJFF4{XQYzfeFp8qE^~caMTFCB2?}=Xw;!;`zvPS z3%_JH*h4mK`zX}D^t#q5n9+o3Z9zi61ISxOBbn+$0n{;5e;Gb8LH z;Cr%yT9~njJ7Q$>VZ6eN33XNPAB+F4u785+8XQM*?(QP0;wMDl*y>(6;Bwy4;%MCA z3B;vRu(sxqrSWnEZ>ar~5Pv_=UhUYd205<|?s$1tW_=*q!Y!6fiAOp``n(~{if`G9 z{JvXz*_dU!6y2IAgV?|^sHuh*%EeQ!MG$EjL8K)MY}bC9+6BI37zo-o9hVPWomSCG7}xZ8jpG?Y=HPFm!}Zg+$uSw zoQZ@O)FP|Ib#~+`&U_P&@)^fXvl-<6=xGnDiDum0dZ#v z48{P6s^=4EsDlRXUNwKLDc90yj(Qv4qR_Ux65sEMX~GKaAk3&P$10L=g>u1nZI+xN zVGrhCv}J?VS6O>jWCzU+5}5XQ5-9kjMp9bF0jDDNe>^n%b43PFO)cd#iAfn5*{82K zJKgl2yj?1_1`?U}M|9%NSVeJr1lTjmVsLLD=9sJUeG-ZKg*C_VHrn>DC~gTXkS+_% zOl_Wg2B42Ih@6})=k&l4%Vw&@OSI3_zARbpbzzx{x*F7csg3!yzIO9sg>nT+n(hIk zqI2n*?u9Imo7dgfqaAkh7jIr#UCGb`kxMX$2%6dRFP?CrlNwl_rFyL5Yc-R9=mY&6qtV_}({vT065W6?@_D@s=uqBsSL3C}(s&5XUd$S^Gphag(qx5R!_ETNTW;6`>k` z{_h@`h0FOvGHi8qbt!9WYuWLK_CLg^L+>CjAMf9;O=@bEY%txrB?RcczOVQQok<71 z;W|a|*frvO+nG|A70UGbzegA&KJ&> zDteaEZ~X%n>8y;&wOj7v{A5frX4ldZvUOB@`u8S!V>8VoNgdhM_Nn4JVs`A}A=OC3 zh^P-U{AUs6_@zW-&y55|09m=XZ&7ci=D!-Mso zsmdm2!Cu+Dqv*3#b(R1*8ef|)~ zMTR{gxB0%3d)#ytG|giPbhR(Hb%lZQ5+)||!plh3#cYAXfAw9JLAC}W!QJg&B_<%@ zIKTEzF$iW@@VUJPmXqHBX=l1D5S7X2{27POr3Nl%^YH_ww5d*H(B({TIr6w`P4l!C zv`+@U6OKTWFgBw1FurUmLN<<<&$lhLn(>DdFcU52uL~$+5AEwVsACqdOC#0>ki%&9 z(ZC?L)3)IcTJ!*s`rr>`0bmB@Oyc9TL+@ibrqzS0k_v(`9y<}-)QJCadRy^Zs3*wB zbX-xH=rDr72zBk;gI72ti})O?SCAF!Te;k^a5~S*zIS-kXV8kjkwD~xkI2;BlflzP za56c-(Zng9uEYpn5oxf`?4M8wx}Ss4p7mUYnM1|U=*3hDk|RG<+cv$e!g8~Y9JE(ZFc0>bC65?H#95f68fCVRg5I?lpPUfqHyDtMDk0W zqZ1Q5HfGP<3tS&R1*yzeD8m?O$163gTreg7^Y_m$aVS`%QVtHRg06eBq?nj;SHF>c zqlozbh0coX>f`F`>$gnyKy4GcLP?K)%F?L4c<}`6Ob=DMO4S0QV%-gs3wucrBbAMe ze5sTtii_qu^5IY6=_V~zE=wz+HGBR6K+3k&%R#u+eU7ekA1w&tO&Q*is|=emd7)`; zz~)@2p&B50`(T~@VV>9%owku0#(&<~>);+L&ttWZuZrNNW{>0*c|pL`YF$v&h-o+b zI`Kk>e1DHe29!{%TvcvW$v~$o_+SMB6i+84db-pxwlbBo-Tdw;F})PbKa%B~sO3D~ z#{)!&Oc^ex_pFR&=2CXt!?7~jaa~(-8gIV>EJs`^=;SWIMOMF0>YEIw2#^2zrLLtF zoI`b+6T>ekdht68NrfqlYF5hK{j*P*c7#P@ST9B0{!)-dM+3X_Mr5dJK+DA&T~{Ut zp{3th&<+Gu%OtY>7LG?m;=C+hRR!&51tiknf;NQpvX7=oUYx!_K(iI151Im?ttt~rasWRX0StXgOf0Mdus&%X zdqz{`MysHFf0;^eP*6JD2V}F!MELrDWT;^yuiNN{L2YeK7Z1HuEhE|*6?a(kF&@&g zmTZ6CqX)I$v>70Zi=7aG9CA|6#071Wh=Wu~0#ijS-g|#A!$vbY;3=U79oK*7rkjRQ z!R<|MbbuUBDFNr|t>5@{P-I{Q+2Bo-XpSl_Cep2`1GRHZT%2iVFtaSpywYL|2GaTv z*1@&`X|$3EIA`rf<#B)-GryTxh4sxKV&PX`98bU1Z)^XNan+g@mPf$XnIwON3i~BP zn}(pUQ6(RX$WozL*HYcotwd<5TuPlkj1MDJ?uIpbrRwB?w2u;v>Lx+ZhT3J$4h?|R z2rNzP7JdYHqF`2k5&_y^ihl3<7+g}=-z7_f0w^*c9`G>-nrRO%R^H2lEafjpU8QL) z-m_`JgIqnkcp{4Lkzglecy0@X2(M17(x+*BRwzyPIbIZ`nCtjQ0 zF59I~5Ss8t5zs)UP5an>-H@-aX%QhtprB~fdq23VZQH6Vo9-E{cb3*{~|BG(bvg>~M_>x2DO$ z3iLib9pA7T5#!u!EjE;H|KO27Cwp(S*2YgK4S5Z__VqMc4yz zLTyhbUZuF`izg;}2rxK^l#B?fEVu++enMWEb2R}1*jinuyVigi@Db2wlKDS)zI;{x z3B7>G^RnRU=;%G~*6C@3yNI_|*xzc#v}|U7QL<&x&W>098JkisVcTl}L-@qTJIjQO zA_qv78_Q5I#l=fG3)JJIA#bsf8xIi$+Kc2!fKGuMSTk;~OUDi<7eKK&dxwV+eKDYR z5~Gk4+;ir0=iw;6I*V;1`}6Rbs_o&*ey2_ij0iUJPa|s=TOqj^KDUCaZ`(WV(Vd*> zGd+YU0spD(V&j?4Yg4Yz4ofKob&FSFx4b?S6Uo1L`C5HQQvf;h|1Ml&1l3chuU8K0 z*fCd6x7SpKH!;Cs%#Dl$!VoJf@G1#R6cY|xv;oE?x)zpvWI|lsOYPjAEnaA1Iz{=+ z?Z|kRYc;cv&v$q^p9M}e@^k9%yzP(W85XNbD=IBC?+ixo%NCGA;0005iHw%>Tiula z-#~V`c^AwdL(10vnpExl8B#f0aF6cv1!T?l5X$8vA#3$1@SR59BoheKJx_xqFHg36 z@VsHjz|0mCfs0buG_|(^v<;xsh^&N=QOR&;s>0ON)X}t=zOnhjT*ShH(WIy5KK6|0 zu4Q2vtwk>AF`F(D>Sn^W8ega*#q>Ak&+M(8%m^a71K%?4M2Hj;s=6*mjng!KsTkQa zoYp9V_^&*r`h(4OZ>j<^)a3S*gdGzY)J$MgkeFN^KPM+o*_ndoR*nW3O=X0I5JC|9 zZ{+Q*xa~~!u=dod?Gq!T=#Gxny^W-#6iOdYLYvmq;nv&K?t(l4u6JJ$E_C3C&iK;s z3Gp_gOK0I;o<$NyQVmOCTz zHB32YYwGI{x(Pmqu83V9ch5s3t(4;!hKT&CLeIo6{MO2wF>@mV=$cvi=jX6%=k6*i z!;Z&N$;e00D=w?mj&IMdu)WsB>x|hcxvOJT{-B=*`M$&?VM9Lvm3S+Zs0qF{v?qapql+ zB&yji6Z`<4{DtIWUsn6}rtf99~%S|~@M(Q;=zXZY^kj~>#K-Q=ahqW40Z z+2ErG0K231l<-SQ8UMr-3T|1hY{_0bjGWkFVoHn0+~tO=>73m73pfjKTkM&+u*n2* z*GGcZ26P|XkV%BajzGTYgyy`ONY&3m992{|HHk)Kt7~g^I~6_ZFJAok8AJ+*gfyy> zsn3{WmjfvtA6)I0_$Up`0r2!ki-?c32`sYy3$<^-N<;ZpTKfi=I}UQC1VFZOvdF&P zBVjMMt#>pZ96nBC?fwWyJdyug$07j6AvG8TPF0uX#sQJH*NY|abwORB?P7P(zH@YO zLtAy!0kH83Kn3fLM{)F=CP+XgBScy5-5j*OP93X>2%=FOwN6FJIf~bOd^@)dKdO}g zJ`-*J`NeoAsq%F4=K8v`TF$5jm5&&oK*wlKNy?X~r&jVJY1#6IL#HYw${=MYX~udK zL^R-gdv<$>*rhpNe{tEbrgb_#t4{3JBFi&+k)(D$ftJupR=8zo%N={NpOonV#8-v3 z0bu}J->3O#Sc9yeE{Sj%jp#kB&W6{47^}R#*k#>svmSLI)hezv* zdc6FbZ2Yn@Wv-OY;LdMcXnLg_g)iL;Eyh5(Gf_l0n#9P1ixy|*CZrTP$4{L4CJj7Q z+Muafi_zJVH```=b9`{`7@FHU<1#^iR>*g00&WFfOuGkHb+q1Q972>_*JQRLjk&+6 zyEpy!y(d*LN78U+Yn(>iu$lZSFAsm+_rrM`85BpcazF-GMMOe?{1K+dS*4Bib)pGa~#|l7QK4$dV>LI;h-ayW^}-EW;LgwJ`IVUTL(%iqh-5yGny;~Ph)GRdZ93ZO?UUa-nHjcak1~zDNt7`Vudhd0xVbOJ zao)Ykkzcd%nAOi=B%nkWI;JYRFZRq{0RUS1!aiij+sL;mXtya?^4G0T|L?#9?Lbmo ziejC$teh@d&}I1jgUtID8WTpwP2aDfYQ-Qa*(ZKR1TaRw`t4FF5)SN4$vDJ*JjTrh zipq8J43yZ^l=J&jv1aNNR-OBY1eOXAEn=#LVRR!Kz~IgFQ&Md4HbvHQ%#mCK(VAR8(ArlVEw18ppmwL zx7Ef*swC4XyO#WI7|C`6-v{xue*>!jX7k;haAN zH6Q>3esdkyeKcQ^{4!Io&EL>lo`oJ|MQsOcg!Sjnzl}H3tHXsk5fo|1qja^pIBSkp&0|Jw& za%Po{g|dCio2DaK%|%YtQX5~q*H3s*Hd21@qtM)?$9KK;YDDhc%zLJz(?jiJ>x{tx z>H5{3%9m3w-w0RIs=`n6LPq`CHo@DrvNsj;-()(uTAezswn*>sukXfz)6mp#2$KL+ zJOI`yaeIeVxSihfYUBy*d*2KRj@8}X+#MFLjR@r|?b_93LM&+%WC*0fAa}uja5zCh z?xVH^R^m==q@lwy_yY<+36T;QU%q7v!JK5SC#JH)Azk=qp>*hyS8^zGlHu5 zV!${fpryO9Y2Dx1vq$WMY{Fx3R4<2qND!_1H6&mdXD@ z8*PlqPs8faxo;$>-7ljQH_bJ3rR)|=-aI@+jpoxRE}F%(CQb3=n>%Nh%USv?YP7&a z<)MyvvHx>z0-hCWE8L9EVIxpzEfy8{31UjoRW%N537GUeKZoM6YE?3{twe5AIu$iG zDiVOtMdAKx^$FW9EizsooIy4h0*E|%7oE8A(Hw0{H^)zo%t69@?nocB>5j38}GA|JOLxLNwF)KJtr+LwO((% zeX!A)ZG$G4&c$dVhuZfBcQ)!ycz750udXc27n(?JuJ`XDzC0zg^HtF4{O=pna$}cI zA9FZ0hHjakLx_Kb9LUh|Hkr?$jK2vGN^q-EU0|oc%;n z=s!o;Qf(@2Ab~h0fEmrREGX zGy0yL)3S3xOQ=j93?EU& zmZs2-=X@ottRh^d=7IHx{UV=3cjvrZM1pAc!1Uhi`QDe@e|<*i+_jn9rsaVmS3aO0 zu%|jVWBDUjqt4p-)7Ob~d?CR*wN`}^A^Q)ZYHKeYJh9`hu6<^?({dJK*KqOv1uG$i zZbmUVW7zLxFfrEn*$^>v$Gz{FsUCu42@<5SW!@( zilzNN)3?E?9-}^tp^ovFxgJhk4PSeqjv*V4{531`u|yph1bg_rEtInZjplf#LNYmy2l&a`;}J?O1@h?{#2nM`~pIj4^tEN6r5&#J~Ua^Mi=U%NF>kyj?}A ztya`h4+jxSgjl7Y0X#DzGm}F$Ffy=^=bO?w@cSwhHcXxM5mvonOHwe<*DJ9(v z|3UBj-TVHII*vLF&xw8ZUVH7eL~|%RM|mp5Qkq*h4_I+I(R;&o=Qif)*+S5(PW)e( znU~J--a~GU{I1s1wqoOXV7tE~tl!kZRfNrk*FM*#`sw!#+KRhFpPjp&gK)JX>DSx8 z+y1{R6yz~BmI;b!QGmv;=ESO6H*jT~J5Ys0MxuizN&B{Z!^5TB>6tI^PmP8C@b|(Y z%YmrTIVMu4Q|IU*rMys1AhKuCKv~scE7Pt{RQr z>6HKS%6=${yWk1|3xpEOM)xhC{r~!Tn!z|fZ5rbOwo;^_fs~=O9!;3}a+bnn<~UGz zN#A$CMMVQqFHq1$ZUxH?_0&nb6Z&i<6VsgHd zaKkgdlg#E06E8H|bFku5>(Ev^d{Bj&%{dF4rDnqhM1y;`o?ZtX*QS)HE znF*>j6jDFj)kea{XKLB|_wRXSLs9R(R_=2Wn&ZOId$Y}VJsza-*RJ4&f6A;zXS4LT zm1g1=36gTZdAsPwGMEZCqcOwsB_x{KzxhkEPig7hwMHhD!Khv@Mr*@P)>ij5#ZQn^#20szon>@_Vxnhfc}~d9-YeQ z&()5OM~2<+Q7QQAjGl$7J_x7vdu6OKF>eNwCgxZ4{~oBI2N^|u{keB2$brMF9Rg;x zWpj1Wx-Iyk2@sS-Aw$y?u-4ZbTir{Rgh$I{<2Fe>^$920E;X&6g9z*rvghxu ztP|Xj{r%BPnpYw| z)zAyFvZ4+>+0+XY@aBBiW`yM3oyTrgoVS^`zL8y!w8}nUh?fXqqu2f^kxcFs+!_U^ zCR9v$#USgX$S_O}>w)yTvm2dXY$^>zni??TZGM!RzI~eB69%0cZC>|?yU=g`^UnNR zo-y&m2Fh^zJ%Yish0Zxcc9fqwcuS*WNVab>%J4siQ^}HveT@801+T3QF<{|(aJ@i8 z0r7h4c#7Kg_4ULOjIvhRP!~!sOMOKesgRGhmyeDI5_D$PGy%qf9Gt!6*1)LL-LOc> zg1R<6HFnJUP^D}jp%C*gCK)D$!L}o%&4~GLM{%OuftYW(TS4whemNyw=)*8{%maKceN6zjVi^zlsZz!UU`Y@;}91j zfLvhgRRmLI{_{gK2ZkUlNn$Cb+c9FY~kyi_k+4)AnkRrXIp$fp8kqJ*j0fJF?%3c+UnO&J< zud`*7cfTH>qO2f>=h9Dq3e?D)%GyxQrV0t^+v+Ym(Ak%Q+;r`TT6(g;<&w3t)1Wlj z*$Md4o=PfWJ?A%3Y5b0l5^Q9Ux9PnTae14j1S|ZPFPRJnRi!oY_fc^<)37<@i6B+&$&hixK6hUbzQ`sKyk$-3z_ti z3RMP-BV+s=fVch~O<2FQg5r5C2&oFC8KZH+;ot|4*d_6!YzfMc7{%H5w*J&NVFAf7 z-8e5W!v!ADD?8`i@e^8Whk^&P_TfL#4H zwUgspb!RpL&zz*hgzD!1NzVRV8q$w-)bKnfAMvz2c6Apyv^*0g%o{VST3f$SDz^=9 z<-waQ;D3==d)D4e(YcQDr@$I4qYn=nxcqdOJjhvNmo-bJ`Z zHn=K?6~b8ivK7LJ>N>~Jq!dP|_;MAW?5YnU>$UxYYxwfq#IGB-ig**h$TI^yiD$~PQx3d*7aKSBhBO_5AZLOIQ^nZNerUEZUJJ%8AB2-I+z zf+7JhMJ7lL(Q4%dqlF;k8|;*PztBZ|s97RMQ1b2_2`66b<7?3EU|b|Hb#^5H`SlGxw-E+JH>YoxX&(IsXE9^aPEyrb z&>!RXXtxnPVhS$%; z0lChDx=n$OBSbze&}~enI|Hj$${M&&#fBtJfNQ~x78x7WCq*?a`cuCv_d}+ROa-r3 zWj0x0<--wRbwl`gy)Ds0_*el$HaibhPy4#^+oTSCp}xeIw|cb-r?Hl=Px|JJUZ;N8 z+!45@MD`~W@t&w$uy)kje@ykpyOoiZ!Njt6h4|eulCe2=@uY8jgEL6%F30#V`S&%r zo$-9y%WU`p`ZNyj-gRos=Z~ueMhHlJ>{4BU?>c>c_Otz)362VGg@?@b^Jw1)-(6U9GmoanjehIxpW-9)Y$|x5+UD!W-;FXp znR7C$C)#|K{z}-JT7JHNaM4z-k&NIw_3B$jkI~^_;znd*H^^O4rZ-xRy!(_XNB~|3 z9t9`5Mn*f!Cv+jbtKDWwW@?h=cj;Zaykd|P5ni2i9J-kI56(_IoYyX~bA(@eIc_BW z=c4}SvAh4k*hbLzXG#j2!3+Q^A3PJze5(W9nj4KdEiG^S#^-_N5St0UX=28^L z7=qfU-KyAI0fd3AO_>>JdUNQM`7y40m1Na+1AhV0C`=S#V=D=+uQ`bwD3SQ+dZhGl zF&jg1j(STf1Z;FGc=_`+{Gar5<5CC9BuN$-%?V|ckn|O)Qfk*#<-_(iroQst!qJuc zY;b8m1~Yj$)%A|mI-5F|pR>f5xc|K}U_GM{Up!v-+0D-@oSq7505!TgB|TZzaRnSP zNiqpy+BK9)kz|;cF9CP3NRdgeceyUSrYZOj7hfdO552YQDfCAWgCP%J`SSy^|7Qt_ zZrw`2nl!ZOgrnTIZtCppw7{Z7)~KxHVqZ}osy060NaNzam8C6e+&1SH^iYK|C+7@2 zLiB|8so1B*O@2WJe_M78NzRPM(1IDkjr=KWM^mXY%LMbS!P)%Q=A<3#rFwLlXqZ1s zgnw7a>Z9RmKl}IQ*A|a(bR42kB>#KM{{HE%u&}=~=528ESw!GVgj=h{e9B3-&VYAN zd!dC7x8msRB|4fKyoX*9CSEVX)eWhAOC+f>nXY|DN1@hWF~92m&Y6gQ2dnn!%^|Zh zRo5Bmw7J8e)f_1sjIO%&)a>5s79Y=*I?vTg#z2;^BA~N&Vbt^B>^4 z-Z6E$=5$)+uh4z3ZbOsGi=dmzzhj=aNgx%%?S1vD^?P1R^f~SqI=Sa_^g`UZAzYf@ zp2b*>+uvUUMKGa8K~Gk}CLGs@I`A9x8G&RFFBKI;WFMmEzIZAb%+lxyCw)|$NkA(t zu!earPYymaOe!(vV^CxyB_AJ=#>}&z0$@!cBvzI?Wuo5o?@lH$b@c6wLAJMBtO%K| z9k{JQNO~}emer@NMJnQd??-6x9Spn{fI)hv_VeK9=MuH6E*}!?sr~ygbff&*7PKxV znOhnsox08f!TK{As=)xQCoGF*;(0f#UE}WuPvMULoq7ZbO;KjltJDp5)LVO;p1EcU z2}_53($V8=et>JPgkt+9KmuYKIVCCyCA#p0z!Ed2@eGNuH!H%|JV8~cFhZC<3BPU? zM9J*Ddf$3-%EM+At67)o#akDI4EL?A7;zh?%Q^H<5&OAiG;FkpVr<0OA%i`WL@vmO zuCFa_@f9Z9i%W~mEGI;BCzEdU+fmL5zE9I=2XsNssaj#E*xm)5GI$}&^+u@R)y`~t}(|qCI zx%%xm5MTly`Kj(JeT#~yLVQ+^jtX7;NC=dSER;mWLe{Nz?iQ8U?UL^`!D-LwBVViL z8pK&v(JA}HV!@&En>>%(;VbLowMhM)h10!tBCqRHL}uaZIqO}j4;msYggX4pwR~o3 z1yra<-dgm2`wA*f2#b$F4Nw!EbK{U7|2qO@A$02aU#(n$S<>wQe3OcWE8h4SOE*ZT zBbMtG${`EvOeQL?E~&3}q~h{Wbd~YeC%ek;tk)4)px0~?X*Ui{7eBKHO&9K1;Lp0U zT|-*+zeQ?(Y7Kn4r;KJ9rutpkHvl;95zB-FHnW4Gx^3<$Y)v*(~O&3m$3tajwOcf1+0MlD1X&NsMTb z3A+Nj)_bB-nvM>12`#b$A{YtUKT8XWhO>7OcT~)Q`61G7uZhy*SM5NP6`6 zZ{O zkyI+;MBfkk@y?ay)<`5It6gRc*>|V6O{bOsn%dLSuUF>+^C94a39H+P^7219^ZLSE z*d$;{`hF4V)T`?Zzv|)*9XhGf(ttR8NMTj_mKdIA;x-{OPn-KU(?7>)(^}hzT*}G& zgv*k*hhVT5FkDoGq+<8ef|-O52L0_l>E-aQU!@-R3d8gk3`vOyY<`cPxTK$@*boFr zID;Sy7uF(2_@7dXifD%UpWMKFX~mpFnbqIjoRf@MqHmg%APz9}w3L2zXPz28(C^D2@2! zi7;nv+@ff*y*1<)@1Sxnef{v1M9WFY4p*}D7)SM=XY}8hW+oAS17EDvpin52Kuwi1UfvotNO zcD$;4r~AIxMa z1&0WreSq+Cb{xo$u4`&a-(LoeP5`prCkXizH}5tjc8X+Sv^r+Eo2{h*~XA+&H&A3j@W(3r&NH?6}QYa zpjwo~Zng!9_XuIdfmqg%7oitnoSoI#`;D5=o!u{&ipdsg(TP<33D{;pewKdM#j3$d zMUkY^lmbA@Df94$CaTou>gFSgm}oHI?_<@g_j=fO+}SO>wi7ZmlOvrTaQQhB1&ZcL z_LcV1y3U``z|q=u`IDl;A{&kluUNYtrGw17>lXm{y-9LcEe9vJb?hK%27^-SD_}vB zlap&#&2elc>Lv2IKf}r-q@Z(CMheIP;Cb$5qTni7;1#J1S;sBSpY!w&7ZKH=LMG9~5X3z;dFRWjI1VOIut z3;ewaDYVa)pvj(CV{?;Y6%z+@U_n_`ZbKH%Gcri(x1$CJC%ZLlzInaTa#ynw5;FA> zDGjfXEb|BQIxoo4(#Ba;Dxtts5~3a>KJ{uPXYdXh)JGCS)b4uii!HuVMX)m~yO;D0 zKqS4aVe9p?P`X9igF~|>V{UFP&*Sw5Xj@!-2ws;NUo06L&qBk;f6Lo)Htpnne0dzm z?G0^62e6C*d+o8o`0gwbP68%NA_8|-R(4-c{>H8^3gOJgzIg0LxR#jZ-v`uIOzj=M zn7mQ9rbxBqhq8MB7fu>t1)6zKVOS6$9s=B0Fd0d^I?yXxhXXeb&Vz!qP%OG$))h=TM~~8 z@zy=owr$lEe#y#q=#2l;A2%h`idB#V-KW_u$i6Fiy_H@GtX{^h!}SIrY`;Yh2D2$B zG8!6^=LX=rI(vp!kF8k<#*PUl6(VfC6UUDd+Cgg+`JKa`SlZUj3zt^Nuh z-S;08j!GJ57bX_Oe0h5I+)(8{^eQQNSZHG+4ekGuU3fly^63O#aBTPmUkd}-ON%>d z30&lIdUoYNctQyK{~u6IK$4uyTGqq>9Oxx-N=q};JU(U{_<1Z<|u%CsS2mB>}#+%OW~_tLcXTq6@40)WJfknr8@vjB3Tw15EQ zpUdUelarI3Mkx`I8RbV*C=xcdfyIU)fV27y)z)e1Q!Fu2nU{6zRK{Y*21!^TzGzE`@^nFibVaB4;+N=W&QFLJQGWY4L?Z)&neQmML_*$jf zP<)7V+e^f;^i@l1o7>T%Y;sFBRI%XME05?}uRD_0tRA*4GL%iZ_UzEJhyduAOy>Tp@BSs_@N*Q=p*E2>upCR4!Wc2KJlJO zKv`SMQb_HS@U>?2N_V2MxLKVXZ29GJd%zeD{TcVMTGoEW?+Rv>Q?1oqe?vw5d_DE* zWbUb2D!gOkuj6lSh={c=rm(`? zE1J*Ie*J?U?$($`BiT zT`Fyuqrz}?miwp}me2O!S1X&~_Ryf#P;)2*^|HM9f?9 z=Q{f6s>X%Hg8o(oeG)=1x)*CS9R3P2pVj)Uddv`h4v2X3%TPReRCVQ-}V&x7#Wih)qfP( z;4=|Otmk08ixP|CyP^fj&JXc)NB%XZeKvDk_|yM=-H;*pG6q09VcF$Z*Pkhd2{{=XMg`1P$3|pq|AR#NMO5wp}j6pgC64C zW{pn3ncwcWnH-&)Rgp?1>oxn;Y(~af-8mSneQ+tFW(O+g3L~`pk*7q+s1G03l-tIC z4lP}I1P^l@avW|C((uMe)6U2)EVtk3YaL%Prc;tpB*7(-RhY8T6-~3R{4B#xg-)sK z%r0-&%J5!!z_j`8BmRH4^;TZkKO9FhXgin^{pQvb2lU%@b?t!OE3->=Mxi|SD64NM zgUPi+#+Rz*XW$eFYEsi7W)-cTQKvenk}4Go2na;svCIR7Cxbj`%RZAhh#*wgA7)<= zH#Z%mxJ#2{v+v!tymZjV}KWmwJk8W%o+y( z)$@iDxFHI4987awOkzv%HN;WNgUJ*4gT6-?V&#&&>f8_(5dv`ueT-_y4>mkGN6aB+qPKMW}j zZ%`$rN>M&b8BkDMeso_)MMtD*zA>P?T22AE@WJoRgS)SD#K;we*0l0feNmgD-sMjS zlBGR;sK%&gc_0SvWdQfImYghGHFWGDU_;J~yRm2@#B{H;LBHK5ye`PZx^0dCj zn7+MrMWn4@LW&$34gr}R{U0tsbfG_hRo_??R{=H#lQKi&y2Px~t8zNu%!cE$s-bN_ zulV0BJ`W9m2?zBLEVP0}eP%$R{KAQoof}`=;2>`#B{=zCD!vD6%Ye4NFQG$I2ce_F z_^9^UUbzMj2&@@y>sy@&_?$=0pU^R~-EYj{tYxn6R${H2>w?OhIPw&!n`eIa3TNY+Ew&-Lm{7q~Kf_T!Y z64b{(m==FBFn~4ZpQ$L_GtzbLQNHf()>yZSqXasRJ!!CPZKMWhXHE?vAaf2w1{Rh2`ajH>aBt={!l_ zzI{tCkSBnepJz=@rXwf+7#tev(5Ny38ZS`MB!F;0ev3G(U{S`!a#PVtt>R|d2@SMX z>mObG!PzyuJ!gBz!reHzB_lxEf%dCsV+$=Lz}b02j;~Z*9E4x&*q?d5rHf1#ZXnRK zJcWDR;0=s;Wu(0XZN0jub{*ffoWk#iA}gPsPxt@Z&LwnsYF0K?Tvn>V(M&M_Fx469bWSc+#G>|{X_OzcK6awqqZ_xaI z|Ay@fxJi2dYvJl;b#+HxC5>mm^86m%Yf|0I_&6(wRd0oys)>11A){ z%GrLx2JRWQM_vCeuW9j?b1tjARCRmntAaJwTsr)xf-e#EoS25CogptJUA3`=R znYzqTEq4qhUtUxhbo`8NYRiKlN|^wl=gvJddEb4By9Q!(fnPWvWqIvhE|oq{VK*JM zrbLs8{IJ`VgYt$5&^dm*I|9JaIL7-BA-|d8u~{QhUf!^Yxtk(^;v)9d>RIZ~KR?oz z29&po9&k$N}8{&H94;| z_mjgt%Uq({JZ=%uc*k9PJQMOdevet5@G#lcua(Oz%sL)1{@bygcU@lNa`>B@Y;LXI z%)ugmH!*SB8BqNw6138VtSbo<#0|Fw*#OTd`&UO~%NXmilU)E30x;0I;CZlvo6%Gg zmy*Kux^#$ZY_urPpy>AcZVZHPHG5b_zQrWr9WJm({;Aj(zivwyLdIz0z>&k?UK%1s zJ~lY%Yi_ot#$%>l^cdV+bUBv}uIW4X7e zRf!sSezPb?Z77~M2yQ1mS6cGz`#=N>71r|TJ~|1i(&D&QNKqqWn#K<`>&pJ_a3qwm z^`|h7M)$MKRc%Y%7ZVd2?+;$Ual-Y1^e?p{otaK_~|pGHgw$g zjd``=N}y)FNdfCq~Hv%@Hp2dmTTBStsaViTSI#yY3s z>kZ8U7h*G|>yv&aLm0C{uTUKCdvm$f*4@G@T{9OW-hT6@Y}_^Si(6x$6r7 z3yoRU{4Qm8BJiF5fDDD?>)!6*F2FXy-Ok7mv945S{|mek>^x_VcSq8>Io%O6rpShc zG%>`w($!T>R#qfY$U}543=v$t%VLo*^#cdu#?;-i~&U z6)J;=pj(#WQpx=toC=Sz12sEINl74H1S>fqQ@dh@5ZL9{<=%W6%CVD_#$U}4$lp3k z^hjls-5CT4rF(%_bvDVPPeDFx4IJhde6yh7-I+=S4+; zDB7IR*4duQE1zs^d;aQSWL!^XKU$kG2f4TFiDP&d@{=uE7(TLPiI;1}JGHg{sdXBYPgshck*wMn z2T6YX2mDg+2u+5+ZOJUd=d2_Is*m{SEuY7eRM{W*q149=e5dSdGAX*$PArTO@~Jck zEpyfpYlL^C^o0pDI4`COWKm&1ICHL~_~w5{-9APQ2{`e06=%2dn)`O$zBl&^~h}Oo~F?9OkZDI|Kfy zcycQzL7|~Bar$L$=fm9A&rOr7?JO>v|->dB&K9W1IlEiN9=V1<`%Vt=Zxbcib^XF zj4(6DpMuMW`SOmL&RoW)^by(_>)Rl`FRW)a@aXS`aFokflZAohYC%A z$~ZMn=@;Fv zmVj=S6d=0*?JRJBm?7|Bz~zJU#|%JXvE+-uUE7XVE9xIYTDLiH#VfV^BM$ee3o%5L zqVO%^%D0X+UsCEalp>t8{$XV6q4)Nn$!yt1*mtwtmu1XkXXJ%%Spqcsl4UW^Y)9v` zzx<$0SBq@@hJc(g#AZqVXcbjKq$4DR7wK^U&;D@bA(l*=l*A4h*b|UfR1gx7SFrF@ za(HRDaG5fAS2HjXc4D>Ue7q3278xnz(3sTyKaHXNxU!V(`(zknV;y(|q3UWQzb^Pj zWWC;NQHijqI4r@Lp@U@?+W2uf?(9!Dc)asZ2W(B6WD$gW+Zj)El#C;Y@khZEg|^pg zY30c7>%pbfHO3%JyzzXreNF8CTW8>#!*gnI*dR#-fBirM-W5^NXiH^Z?7zujOV^RI z^Kl2JrYn8K?!-dN}>U3rSCyW3;eEh!CI_c_0Xc!P|0ae*Dr z=%|MaZMSaJcjG1{r zl+u}+y7KI#?{FE#bJpBob)!@oWDwfRV^J~3Ekmq|Z`m0LEh~IKX(9N-efiI6Vs~z# z0d%`gllP#5_<-Qqd^~j5+-yuOvK_Hqo9)@iat+DdMJ!Jax>XqyaDYL6A*iu*xQ2r1 z?-UqVK-7bSj5?OBqJR{z=?iK0ZTOk)GinFav56$Q}F z1wxj=uX`XckZIkH1rVREMc_5d2hK(;J2u~a77qo{)HETY(rhomC}d#gx8P)mDpjf9 zgn<~)6M1JW_v+?GK#FHf9Ms03*<7s5ZEQLrgL&q%)lZ4hKZs~M$ZYO)Gbf{1q2i#W zGow?(!N|;8Ao|`=()gQTXw#jnldQ^`>Bu{naG@-&+VGR{-8+-O0SEH6|u> z();3YvdI1K-$_2R7NNpZf6Rujtdy0Ld&7}-TZgd&c)*at-p$P(=wm+fWfq#ks-rWA1t)T7 zgZ_p9%Tap(#wD^A`ZgUFk&}@vTGo8k_iwoUqgtZm`-_IT<}16OR|Wm~Kla8qrFhtZnp_5NGl-cHd4YVzY*|>M#WCS00?+SgL%#BneVST#u_jrvEvMQwTnPZ=UKrKi0ymcsdEr) z0rx5W$pTrR8`s!mNeYt~$rrNb*!F96LV5|@bAWZgpdgQre$On5O2nPp=3Oix+Ptw` z?#oi;ps>euQ$SP-ohuror=)%rGdT%sm|NuTSN`UY4S1GK&RJ^Gz_gXK4_7b+!Ej=zf;@0qo_{YCp zBh)~yF0WG?d}5EC%=%d=aNI$`vNyxcxtpWZ8*vdEjYh%GKe<~O!CPC3LbIIK;G+CW zSXcn4n}WVf&bf+;5e;v)#fdByQ~%{I(k9^KqL+(!I2(;jP(`3w#Q z;Is%VTBKz>ltg^~YB+QJ_$`faYu?lpz)4I7VZ_3apkl3_{3Iv$?fm=^As==u1x#cB z$&mm+BX7IYP+Wmot()r1NQW+lQBHsHr7-RA)MM9h@p6s-y4r@`A|*CMnrAQS&uwK_ z1Vgero84wbmp#JjQrvNd<65;I34=kMBnVBEd})qie7R#YKN4R20~I*X(ch$cdXV|T z_+RZc4-musXl;dl;akY5=iq5=`;yf;lLX_PoJ*~?_2-JY)p#`$bZ;M@qc#gg`tI4( z>rOzDC9z1sK;IzY?cXn{FI`6T1%)0iDgYOrrQ4E#FeH#k1(6~6BM>W!433OUI1Zc* zFY6K^Zn(L(#hJ*j15g`rzI=Y6D3Bf=r)H?NT`->tBW$|DGM=6`*Krr3Ha>(lAV>6O z)MS>9ID;X5m_|{zs2d*5&Yxlw_7f|dezms4F+y%jsCXW zjK@oe!CJUkh3q1&CuX8@wGG{-yE|vIm%(|b20|(J1FkJlg z^mjz-o#i;wDlubwUMZ6$%wY0l{}v3frP|PeIPu!VK+Q9RGfd>nlT=w4`1>LvFG&kj z9`mZS4Gr!UMjc^rOxDmPwB9Jn9n>NRnz32Y7zq*VvjVoH^c4ZaZ^;~Y4EtGBYSj#FqGbbDy2u8Pu9L`)bE<1U%Rk3Uz}$9yRWm3Z`iH&KmHUw z%03c2hptoG9-!Uh+z2xOWewPOK%H-28wE5c-AY_&D4J)YJ_yWZ^;r=>f|`thp>e^Q zRru{Nnh*iAt8@Mm7WvoHUT05zc_Gd^w__&hQV(Czr0nYx9ZE+&RPCDfli1ZojMWUr z4%v;>Q6NZBc+-CT=p?WWO8`(b7}C|AEP!B0h?p`VkiodRoCz`4vhFeU z%mGx0Xfywx{_p{i=I!Ohh#qIFWi#a(Nyl|}`~jIMcT|5`UC~~zEL7cLY9Cf)JA>ks zVtTn|kNPj@kzQ*M?i!^sNuzHq==89u((P1~^qI(r#6Edx z>o0g-0@4G}mK)}4N}8PH+qbH!B+$Huumg-r+lnLiMT#PkXSQXT^Bz&FG1X=f+3;Fp z|2En-M|HU+fZ?d+1JH8>F5;usJBGH014}UXx@g@;s6w}ui78CV zzz_i{CFMqspd(|@ii1{o9)$b$4K@U7t-@!eTuxpu_d7{YU-pspN)S&b5iwphYHg(2{yaMZQDPTpFa4oL}c6a*^HDF_lJ+noUWR~Dw zR3F>XP9LNAi?Vflzz1T9iJATW?PuL!cUYf|&QUKNYA=*e{~L520l9knq+D}tSsEL# zgTcj_(sB4Tiiy=FBMYf0FN0Wx5tx@WgWt4(2Rm0o{WBthFtZ{8N`gkHGpxf4GzyCb~L`exXz`hit||C9-o5Ia)`1{o*g*Sbh)=hyns5s^?#ipv7i0CX6#y znxdYACX$e{w|%qiD6gE~XBGjx&ML3nxNfhmsD>+@X^#=$F!HiZ$kLMHquhC44@p09>fywLC zjzz9Na?5kgL0q0>>E9zGYw5}6i28(LE!&N2iEo01T)XrqR?8XNg&4bRJ-s-TL&HS> zg1k@dS`~7O&q*9zbqsmlW>7IIb)r&uCa_9ms$A z3yfaPB4Rhb{c5|}Zrfn9dNV6I-PK9BRslR!lg8!9d|$Z+h4WsT0GT#14-a0p6z_er zJ7!OmsXT~4n{Si_MImDHFAuu-l&OmtH%@P^qP1#5r4iz7r`pdVo%jE33@xgR)9+|Z zheKBDj+Zry4r{iZyJ1#cNSo)o8=L8_|VD+(QWxyl5i^4nUI%1%<{$kE46%^%4#|0>qD_q-p&30#r0pQrBFk ze(4}MK1gxguU)tlmX>Zhw%rk8hraY0N@1@uo}e&e!v}KrB)q&21)*r&yL~3%+BKi3 zsF{!Vw6;-kaMl~P9RRumxMzM7&f1j{4Nb{$Jt=cv)CSLrSF$@bx)@)j_DPa43cv-d z?Y)nRhvv1NKST;Hc=uZIQ=|pRHemQ}fA;v}Oj}*fUF=*?dS=dB{5UP{V0qs9`WKoZ z_%!v`X-z5>_Hg}|99(?{-<8jI?BHF51Et2YXLgzP!pS2ga_@H1yXn;7%iW>c8a^XO z{aveWYU3FOjJlQd{ziMH{YzMEaX%z{Gq7qsy1{m{raf`#s_{p2UX(j}YKmw_7GFNf zy5s3_A(2e4=eP>8vABd8%D6<5*`1HFvi)(|2zSzSf1jRW$*?g%Tb!kdb)`~XMHP}2 zekVedj#8o}4!UfNU0El~VB)^(mduxe zoGz`ZG*9vOcxWD5Dx8Cr|I~hV)S+Cw<^wlMX85#)8|sVp#ogKZ017Ncdy>W{RLk(- z!^FQ2O~gc_J)2T_?O01wWHi}Q-^HShe#Q^kx@kX z*rZn@Xh5N$Bxp|mm0*%??EAz9>s-O<^n1`3Nhw@Xo;2Fla4_9NRs}$tLaNoZ9`K-W zyIOL5cDDk?2?GNIU|_Tf78+{Djte;L0Vap0I1uR-k5IPLwy29ZYO7nj_=C&bDJdrx zl$eNmap3~Kx2&0Ba&kYWl$w52PpbBn_~v%*l(rn^)eiky+q0lKbsgJ&b-^bt4VvX?>TS8Y-ZA#(9DW4{7FJvlaLJkG{^?{|y0 zWo1UGxz4!=UDAkrvzFA54Blz<4-))dohdHqes~bZT~^zJ{Wtm9O-(^h|FhcIo}41! z_y*I&1Toe66KLDW_vMHp5!#ex4aoNi{nFf;x**|>S zqBa|besBv`D8T9ZxComk2Wj)}q^NyA?SqnYB;=WB^Vo^c8(7NW=qsWhm; zWJRHsR$0w&1o|zmuFmVhZwMk_KauS(8m~WG>Gl6QV{x{5c;rMOVG9QP4jqek(N&(9sCtfhjo=_)H7#D&@pMsw3UVZ?ruK{f=|&oeiaLWM2Zn_K?RK`jXrR4n zgksIXG?uHyHER8?d8*#O-4^Y>k{gv`hg1Fz;H;jm2r8n_RpJIh5g?f2fu#WS)mw}RzrxeWnhTld>u#Nl z$6n^$-3=^G9<%xDUwjsYgH)BB8A_q&xllld@f`prx18IP_CKYZ*Uy1@1+#(zE)cC3 zS5>XBcldMCu^v}pfxl=6XZH(6cr7K%zPbMLMPs+VmGjf?xx}E(S0#R3`r&CjpX2SoZv|e5cZO-3~uzi zN7zYQeAy&hg#0Y(k#*oN2rnMb;q-99aeH}TGt6neV|D!Lr=Z>A~Riq31H__*@4Jj;2 zf=44Gqjrlry*ks-!xhgb_hG&}GZ(7o8 zV-gk?Fax2OC}E;dj4>yvl;?;q^f4S&Kv=P6p*51MNQ{Z#>jx9Z!@HHX`Z|%9WUuTx zTEEiYoANC(i+B+Ked0a_)`7by&Ui35XE<}RlkIB7@#b!1hATv)rUwYWCdLGah2Ybw zXv9dDmIJ5IQ1;)H>K=tNa_7? zFGjj@*t6uhwDKGvR*S9nS^8sLRvkXL6q+Fs!(Uhy|eDthS>Fy$z#H4}~voV%FI z#&vv`Q_MBIbC93B%%y?{Z%($98iWB`V#Vvh*)VJZ3R-I=oGKSdUG+;6r5kalr#x9y z_%2$6wS@~={Qm*ZOGya=K!-m2d%J{~7;1KBi-s)k2r(ds}VZg+msDn0V`U?-xMK#l*xV2NTEq z%@+pEdFe&g>kvlmONCaiE<7odN!ch(CqRp3*>i#wF-=$~NUk~`{1 zJ?*L>8o+rFH0NY`0%93t%Z5dr_MEnwy!iVe6I78QlGbct(5H#N{3}G zy}!c=93dcv&8W-w19BtqGp$LK=yTjx*fz~6DEnqbF4*?1`2{%8OBD{q4*U)f_4~58 zEgWfy62MGFqsatsuU!BS#aAkF;%guN=^6qt!J`ZbJK<}de>K=oILF7G`5IavBnC{b zoS!?v#Ka>(Xk-vnw6sEsim6h@O|+~<@bBNd(9j~~UYq?*%U{hNtDfod$KltZ; zFr$N8-&tn3y3NrPm8TnWx*LAu_6I?Ul(2uq#-P}Xj#rg*T8AXu3!pXht?t4qA~a;6 z&Xw(Wu*k9Sc+yIAr7&!SNFuDKV^->gXoc_*$C8mk!`ZOhj~`I#Zq|~4MzBWja78P6 zR}o$nT)barnwxj|{9Gz=2rDY$C33STv9E*y%NvslRcfutG<{`MmR;8^N_TflcS*NMigb5(OG$SN2qKMicXy|>beD8X z_t`w}cgEl^cU^n0m}{;%4Ok1I-Xf@~dKekKo3~MXUMiXDy6u|a$JKknvui_A!bByA z?`~S@|5uT4apyJQ^pC-9l7fw<`G3#+7X3RMR3L&`&F_)qI+{m5s&5HLwuNLYLWqgm znSPR%RE%p7-pwL*`L3muz0xUMpIeCeVDsko9aC)G#r(zid}$X?^>bi@d4Dx{#>e07npg@)T*7VyEONvHZCXldS&Q|Z)ZxJ~p(`;o z>Ugkr;0c;mm;w%2R@yK4*-yn4bC?Kpm#3$O2h;bnOXtN*T3rpIf(Ej_5Hf_twVb;P7vPN-o1VUcVT@Ja2ezkjd!>ww!g6yVVbO6Se*+C& z4%6TM;?yU8iNu_qlXQId1v|vgM*d`v_EdP64*i+4c)`#=%lr`bkr%$X8%zg!q484N13#{>0r_uCDu-@l`5 z*`tlWA4qlL{!>0oc-_whUpQkRXKRQi-u-eCD+I|A@V=>#@HZ_F4eJP61iQbCAMflJ zAnvcO$dhGOx|SszFO3HEV8EasOWN2Z$qTQH<;0u-V04*}A350Y#2W1|s769mi3kF* zfhlkG)J$iLtlIdGmN{cV<@`J=A2DESyz{)S?QSX(Mcs`FtpzUb9SU>q^I~S#X;Nu@ zeUD7~)h*?e_y4=G78v1R1gN$%_Iancr26Y#mdb1y|GC^3dWB^L(buOP=Tt?I+D%Hr z!g#Ou;O-zV73Jed@93eRI^T@F>O&}l!uMl#|B^>m%{cA7{M+i14cQN>P_5 z^q6r_9XSiov}rBcaOKP$rh1QByf@-XRm`Obv;ZI!Fjg2OcKgBZur4oubX3fgFEk;g zCW|0_-Pl7~*#_sDV1bM5=@$McOx)A8AO9PGF3~~T|S<&H&W|wyt7MMQc zLJ5*8Kr9Ir$BswqSu|9Fz>XL1u6J z7`5hmNBMHIlKQvb)B!ZAe{0X*k=JPUS*e0awfoL^Oy8E}FQ%2cGf6+Kj{hwiP5x_t zS?$+Vl=e5>5#||Gs9S$qv(;obA@@aQgo8$H`rh2N*6wamsSe_^j z7{<=`^|e1dzJ2(7*5@`MNC*H-KkhyAjoG|gu{S=v>pIESc5fhIJ(75;{Qo&o0Oo+x z;WQKB>?iHNjcss3xA&E!g7Ho~C5KY<0-OR*PyA5bU21qgUe6d5FtFNwewYI8Rw@`6 z-H#`3rbxsGLK|}z&`(FDO#Q@XAWXxSbmiI>mWM*?i&f|xH%iS3?ZSQ>$SFR%+XWy} zkGeixP>PiUgWrNdw-xIY-X)sAE#8t*z=%mD>XiXwwDG(>=qa+gGF$o$^nh`uM z&z}AoH>jU>5udU1l+hqaHWs$n5JSCX^NDnl~ z`tIcZEbR^$;g6TrwLy-&fetA)rSzi(DyM;w1)Y_vXZ_|{5&CAQ|2?~puwdU03~L$O zAJ5-~ARqF~B&{vq;x~9dlwrf6QenIT+`jc(87 zGjwfYS>Q?@Yh??LD^7Osp7XkMzz|d_*FGE!s*VNQ{WlUv z?cLvqY75nfZbcfmdUf1MJn+EU2GHw^D@~Yg16ggIRr+c9V8s1J0|l0SJn<`9t0Qa1 z%f$);iTP!hUDRQ?*V6h3?RzD?iKOd!?y24KCQl8O`%w0NA}9XJfsQ}%RpU?oZ}y3n zovy4}W^4?qt^O#>UL(s;x?qZVHPykj#CECVmXw10l`hOFJ97}XMjnc->$1GX(RN0P zva`Df15xugFX}pmS&OdSy$t_H-hRi|?0o*^u*_8UmtLse8XMoRxH5p#fFnZ?Kv7t} zed7ZFO)xB}tYx~);|C&9&~yO2YJE~tS^MV3!Ps9-gn=A~Il1{|IMTH|x3nta*Huc? ziivICoAgDG>r2PGZPn>n0(TJj9-q~uHb0ZV2=e#jzrFqU(8J{>Ke&-mrLL%<{@a>R zs2}rjf72h_wIDPa3M{2p)XMi6bD+@?dD-g=FNH*7m6p66b8feCPksdPrOc6R^;0IN z3=4~2FCHF0+L4nEgO-{Zb#88FvkTwjGo(H@cue1LmfzR|^<3&4oaaJYzs3Gp(n$d>3(nHL&R-cvyBz7 z%9K)uUC7Foi$My55KYj9G_jG=@9SnaF(@9k2_4Qs)R zGxMP^a$vc)?oQ~63RU#YA9ap73HBXz94288G^iO*8xX1) zd;qyx!Qdl)_Tv<`h$qf@u*4+zK-6uZ&;;Tz0l_6`1Ngq|=EtTJXMWignZD)~sNs(B zAv97J_rHcN!9QvJ@ZkMq1pT=GweiLZ-tYAke+YB6ys^WS7fk3a)r85HEwaDaKvh+> zgmZUySQvif_GL?EqkA+y_CX=gpte&1Rghs12Qcr1UMxFepc0F$Em($z+ zf5%uVr-n8K{w967^?wZHNZHuXS3OGnrl)}+?qn*5^$xCi*NS}CVp*jTMby!pP0gr< zp+`g2D|DuoXk#cP!J?H#6aM;T}%GZ^e>`k)HXBU zSAy*cY1*F|o&&FJw;_e6Pg{A4d8sFS55vNzkJd-}QGE_B)vfcVu7V;YCs5eTbUC0c z7rDAq{4Al8lMyxvK@EwXLo#FGXM$^`#aOHdi^9NTdy9=|mWVzg!J4WtLS30eKKsUz zxeV>+q(}|+WEX3r;KX{c1nPVD%zE^^e3W9s%w`nuM(2%+TsGo2D-u}x5PgIqlZRy7 zkbmMk%_jAP>FSHDrHFEA(1(WKrQwP7T0*u(Q&jY;`E1r0XAwPp6|Pd`{YxRPIKhCS z#j95Q3V3RQ;142>M3h6rYBVmRf1FGb8;KLgjXnL%w8EkN`Uo=x>wzf(KQLRofzWbg z!c$=-nAw|U;z(V;kK6$BSy=t9SiQxy8fuAje~y-@^_TVs)RIrWnPYPzrG5B)Z(bp^ zP3O(41NW1rk0-4hfvCdEU=@U^Wp9P}vdU;&!pUfA=-co_dt({esxDMA9a!>P=Sn7->V$s%7T#}l$>AGer@5Q7R>yoxj^TySgx0U%oPIU-W6 z$}tBzlmg(g!n)G=tEc^h|Gt~Vh`CvCmPoMJFhb}K{VGF!Y!+>;gZ#R_4ew}HRD&yNoGoDaeoP|NJ`@P0i`Xgjrt!7L#$$3mLVQlEB6*q z_weE2k2!R_k_^He#5uS55gpWjDC?_+QxzJy!d7Cb87%39H8sK*i!-TkZ_bDpRtF3~ z2|?aoEqWWnOb=+mQS!kL@WS=+)jsgRZs747CVmTBk?pk-qMUHl_>r~WL7sU%5t@1Q z@-Zg65kkGDA;%pOkHKnk#&be_+HhHW!MUVck(8{zfzb2W4hfw#vXO3LXpuCogL3vAs*-DP=Wk~%oKaeYrMR>7NJe!6v4-{wq#@pfX3zN z%aFjNV;S-h9Iq9}gFxJ{swLs&#qgwERunp}?l%BC$Hj7~wpCUzc}m`sz$ltQivU%7 zFvstflFU;@ey=OSoQ&{tL(QmNz!Y+n(Bd1PO$*wd3E@0K!r%2ZZ62s%e>^4J1YXMk z9;WG;{ja;}8Ye9*-!3o7HXMd4rWSOyMQ9$Y|R7Zs>Z2 zFlhp&@PS~(_;ZD3l$p^8O2onNStu&s*xY_?H!2FD%51B)TpvPD3KJ?ZEOGEg9=qw~PTjmT!D zETcL6-B8umyeD!Cxn6ClPzg*gAW7Uc4`Kcke46h6zd7LfeB)&I&Zt`c=aL-xU)Smh zO_k+8aA#Y`!Emh)^Kz1(E)mgF&HzOBu@Pc9IUR{mEiA0?&K}f)%1v!V)aS3bmhdFb zKG;zta4>bnpZv+7QpWTdsVh_JQuFp#O_n=&%Bhl&shg>sjVw2`UgtmC_`ZLSS`|Zo z#s4RHP81mMmgAT2iAg5}OO6Dm5m$+=U@j?cxQH}%=}_p^QrO?qOvh1~=|A+<0`y}L zNn#TginOxt6>xG2xFoac6B95BJ{TfRYjxTNNKm{_$y_W}G7b*gd?O&j3t^SH-}BF# zU--;h(O*HT>r{DyP(_v+J6%rv>AQXU@9*4&!vCPK$=de0pp3kzl~&NUAeG^4L>*vM z(tI55$a6^UPnojDOFYBBii;;AxmZ>*>l*5&L?4GE2=#PTykI`4qCOymdf%;AknVa4 zCFvEIf0Q6CCv|1Rz2Utmj1gW5?m+-;j?a0d73hDnuAa-7*WeBttcl4&u2)}7K^8fm znZi4Z+mJm_*!@cUZM}^v|`NOu>4o77-J*Q*({lvU0D&Pa%m=Uv%CRg*C!A|93JSUq5{$6%ZQw_Q0=Pi`yRi3wPG5)0knE3~*IaL-aqy^b&yxFJ0MJ zTjB5_N3!JS^!lWb-Q|ZiLK%kCVp`}JW(+i=HNjEa@GEpl>+l0~dTsDk50Ij_w!HUXYH7`?SKczfIX zw1AX%KpO%lkWOZe@%0B!EA|o!-X1>2!b$=oVsVgMT-98w? zbB2&n4I$|Eqfk{@yZyMu3vLSTalJ{iqt^oEqJ#>Z;yfs5!qiPYJ%wuoqTHk!d9INY< z8a-F=LPn<24@(NxR^Z18w_urR@1yg)Wv~3S&-Ogs!h6)yqi?GG^-V?TOIQnzVAl_3 zim--e6wfFgGB&neFhZG}FO0N0FEv}%)2N1tklCpJ)Md8NF+_@@uvJDAAQM6HCcT_E z{WRSOFjS2D8v*O+WBYA)UvD_Fi3wE9b1$YTdw10NBGJNTg2T1No>wM9eUFW?ft4Fz zVQbU7ZK8NMCfQ69#{5?$YJw^;0^9W!J0<2H0hx05q~#NUZ}X`R>E2YI$4nPMJJb2qI^3uBT=d*=*qA0&CG}i#j5q{RxDH}zDkpf zO(M1CUu}nx1BlYmF+su~r@>$V2o8WfA0DfvJ&z7T`w7Wv!S=fk86s%^+(a$0qlhzg zX|Xo(jdr-|te0YNSPiQGv#@99<@KaVJVLDPrvH9VH0+TLbpQ5SzyGLuX8kP7L zhNVNT%`GFV|AS$IEGUW*xU_@Hb-lr)cy6|bcLdLVlk5L;0gB_igqH6)!|Qo6_;%$& za&N3iXY@-B4aD9Y(FF=_YbE|JYso6FqH9H;?I!F(bAMV#w2;1ZfTF@Ml;FwszL*m; z$sw^ZW129mBWi5mf@V1&$Qnbw`leM$i8j6XMO*fBx=6~&C^aj7?U(IRl_b6o+6wXC zou`?}aRS5XntCkZ8t;sD-LPg7(BWXgBF}4cv$b<`INvlStC#UhF^2#Y)FAlw+(80) zm9sx@=i6c58RBvH#h5#9`1hOUn!9bUB|eh$Vb{Fi4d>6r6K)%R3;CpW|lC$vYtAxHP@>Mn1rjUGBh&Qu7c~l7Cbxl*oy;QBKP6*1lpOx zaT(3nX0K&+7LgX2TrFOkp6R*>>Q+DJ*@8K<*?2j%pdenGZ#N&bhjR#B&&CCIC6_*8 z^nNYz0XFdho8{krv&wpB2Gv!*|66xMEX4$U+>ouKd8<1cFg4}R(KQ7Vlj!+W-~_3Km9)vOV7W9PRS3-bQWT=MlSwsld} z8A#o$Bb>4eNpU9k|JJpM(_ar^UVey1{SoY?$5mmU$> z0#A5Hnc)x}8CQLUf4Z%Pn_rkQMB>`pp5yF5PI<)c$eI}6xpJu=fk}Giwr z{3E7NSp5*Ybc6f(y}Ea=lTJ_-(_%pb^yi1R9UTR8xwp&H8I-qI>oFnM58SiF@Ryi3 zMJw7gw^_wn!-rQ(hU)M?)U9;|mh}pY=IB4#GffMjhSu2uuC1Co&uSiYNBmZ845kq| zjVhw=08d?P=;&K62L9hV%MOwxcl@OSXCiF4BQ_uHRce8tkwv7zbpH9rcW8>D-z*H{ z{#niIzU7ZZT?PYnBlsB?0H=8ULtcJilqGswQ_z*0W$<|ZNhBgW*5Vsg7lD|eF8;HE zgMOmJ|B~5`b4U|lsl4K%K|yK1;XCDJXrYo)*5fVZ8U_?+VKwuTj)4KJBXM5LBc*Cd60Y`vq)$Z8mKk3q!QX__atKU?<9t=iHN3LqT#t}yuE1PL_BzhAwn5MsR z1nuQR#;#N{Ms z7#%ZyKJlzS+MhJO87QR8<}H*h5~+!Pe?=q0l>J^$CU*m|Y*;QI^q&04(*Er05!Czu2 z`9Lm3F4s)gY`3|1uysjZfq5C>I?D6<0D%btsN*QJ4H_gXmzF%|Bh0ZatF21}msqHz+HjhDbbTRida*|1!;^ z)vD^XY48>a+2iZBo{cBya?c|9qaLpt_8%X_aK#FMdl?STJ*FsPJksHpzqTZ#UTp+= zj}QQ0viE)i$d=wM-K6CKU;6!Kyn2g`0XgAZ4cC+4_gUzY!}ly6v#i(;V76qFoDN`j zrygW%kkN`t-=A$pp3A08i~JH2lFk3gECXw2bZ$Lgguvb#!EIy%<4f)b_@lr%Y(x#G(bwy1iWs`qGXpw zx|}wxQG=EExBQry2-mi2^v5-Aty}j=H;1P_t%RlA#wXP$ZDl(h7%;o}yv?uWy+#}i z%EYE!jG^BMXmGWg zBLh6su#+{rbQGAYpvk9=wu<%Qi_~D@KWX8YvIislskn*?ZK2O}D-)z!cXj_|Xnim< ze_ion(q?QumkUd@vbHeK}(O^wU2JY-m**$JA`@w%g%vz(I*A%oVx} z&o@GtSDF^gCa@4q@)_YF8?XoTRl9Ty@>+kMjb=2u<@fzn+Y&9yAM?>7ZxpJIjBhNny_}#5XV~) zS(yB2R)g%hJ6Ae_*dXh+rqrgXm@xy#I`a|WeIJwVE{uzc*jT+ih`sOKwap8P5rXq7 z_dM}t(I+l z?LSE^z@~wa^>`(MNxM*cQ9&!=1j1ly8y{5bD97HHA5)ay7K&9%piC%XS2b|VN zALtrhk6i_N`illenDu}Y%!wv%E%Tbs{IzdoEyER;8o+wx`^Puy@0T2tN`JJJz!z;m zeqOcx3>Y`d3TslA@(|#ze~bsQQUx&hrt)2=xVT0JNbMhnq<>Ws05~s97>jHOC$zfa zLNXAR%Vvt&%ws!1jQKhobE=~w@#}>vkdI2go$H7@d%y<2WK?Z!e1%mBErRYQd-C*G zTK!|a(am&*d_096a{Z@xLgFsl&B-Ztn1!Wt`_EL7 zG8RssXi+7=_3G+N;gKoadn<^p=6>M`C4Et|cU|b~8QLsHgq4m+b zEu$}z7@Sh}H7{ct28K>?+!?j195jZ9r3qQzph^cv8^Dbt%A5I>y3;1o!DLqbc4R!RWjsP zr(>_zu5A0n>PUiN4z(qzra78V0lDVe_6`i#mk|8BeYa$Pwq*d%=5UkXaDsQcOSsrw zuqFV-t@}1n)^;X9ugMV~&&A_ki7Pr^V|NimEwt0PK)jTVO&H)?v)0ZsI+8(snzJ%2 z1=7yxN~oSvJ?&$p^*oFo`;U_ZU_^3MO%E37B9f9EF6X@QFIf#~TU#^^`<+LjwYW#A z(~YNw9H^_>Z3z7p&{`CC0$-;h=UZHMwUy3A@j*dkU~nk`vPyrn?Z=9k6J8a-D`s)? zj*+%E@mR&1ZzSIFg>P%=T*#?2Qu)MMSzxlpK?7=Rd3cPUZ7GGUu|o zFobEF9pb>6MaThRZ7=pOOJi6u806>WNsO2!G&cS!XWd7bClpQeuLVGc9EdCl@x-x&>+tU?AL;1{lB3R4#u7{tlWlI{N1pe_L(qm#~ z!|{3fR9GB*(-F|o4sr8Bz#bR<*!^G0`JpxwaOYmBrR3zjm-| zFL?p!ai~trjCe0!T@muG#Xy@JE1@TY9Y`Y{cpRrywJRcefrbawD)K1`rZTB^>qxpM z(;UV57)p~aHW^C#e7&}ApErLLr`zOhgLYQ^tccmp5bPAHF;`b99cwLj>)D&uYP1s% zCBy+8*Rkgtdu}c1T1(>30A1TlObHE0^KIY`4we8E4&Yjc2#^&{Ts@89+jHbmzOwv0 z=q51k%9ktKZM!kjY@Fybj-jeC`rPq*c`Ys{c48A?hFg^#Vgm3XaWA$5I9p>}qn*M4-!+c-TmuQ?*@6ik9`?B$RDeKh0&E@- zw-H|-AQ{7S#@lxj{sM+3skwX@Qk8wxc}_H4QvCa5R3N&AxzYhAoqwNbKvwa&NOc0b z(d@-5LMYb@*Yw&>q8~!cj6SH;jlMxu0szyd1uy79O=-A@Yi90Q; zw^$cw-R96Dh?L;yXW^Oof2fGCQob?>_B#JNi(nf9J)9PaXpi^6zn*3km@yyIF7g#LUKcO`f{=2lRJwf9Dmc62y2)#@|+U+I}`ac)Et987ICT1-uz z^~6|s>u`tx{u7;o{lV!5Uwv{3$Q4wCyp#nXFV#h3w|vT6%~7TKEf@U5y-dj>O&QT? zo^f&1YBGS-43ly|>_#p&rBL;~m3c(uH-S47K5T3WJ$FM~K3y!=Y~{=^Fw2*SgHj=| zdI1l=pySbfgs>-?@$-2w9Fj`GSnYfC+Odk2RoFsJ2^*fu7;iyzZteuSuUy1iL66(U zr)woJSKOVF*S&p0I6q(PxC680h_^#S$Gi4^;2A|rt8VDO$YfXl8SKMNoN8&PC<}!W z&vO{ox%J|WB1F2;fe!Sj2F`Ku(%scGkOOajFK!q3ze=Q0M?ZM3hEM3^v72UCj7lreIM~xIq{FGj#b|Y?FPFo zKuc5f!Q(RQ&ze&WyqTQe%`@yvO2t!~)LggW(6u|j)qcEJQQER4TOc7#XZtUU_b6lS zfwcy(l>*$*Y-_rCCRMhq*H@S#Ezeq-Y^P24xUf1)NJU@lSY3WNKcSV$RfN(h7lTuR zVbwf+%Kn>^*&TG&Nt=BSxhSbqj$VR`28CRY!7BuDGpF2PS;*J zTwlO=KW;6}O&mJw%-smUl$L!==0;Vs_1{E*gQ`QQ>bS#4+JmtSUxYpg6eE!c#5tLF zid&ou#yYS(?9~8Se5dyn{=jY@q*q}j9K5ef# zAEfZyU(@IFf1PSL0_52Jv`wRQmbK%_mKR2hFcg#CYW+TRV+#!J(9b%rCMZH>d<9ub z@BH}mDaPeq0O2Y$OL_6-+z8YUSBGUsi>BRRJ#kW;v#h>yKWL$h)g^b<|1`tAR(zH7 zYO(H2NH?ebAtRiZkxr+lzWBq~APL^plMCf;hPI?wUk4<`)at79;(q0(X-cQ@<%ZtLSOs1T_` zA5u8b)3YnfnqyDGCsCtbi~ek5u*(OG1`Gz##$#{>EG_Bj^-s0>4&s=Q-4?AeYp&La1EBUpTsE^6hM7`5H70&YmcvYM6uGV zDG=bzz~NhDJmWZ%{!2Wxc4B3d5v+Mo9Peq@OV&s`?CSH|OTNa##L9clq!-rZufb|e zt|r3AL~Pt*{Q9zClig%ok+Y-Ofl$IC+9qFCzt%nA{*_Gcfl2%vNXRm|IJtI-dQ2ka z(!2HE8gLzKcOwzxG5KASk~s=EfUffI$Ga+8gn66qTgCTfv|#^FN){<=%73k*(l`|O zb?ZJp?xx=zFi2vp`Ger4tVx>-RQsi|u#hOkGA}oFsRGdNjQ&q^TZiVpS1mQ z=FYoN^=rzV8MeN_IO^Rv62H5BbM~^(a@tu~TpP2s#^08Iqqhfaz-j3t$igBJ0(28q zd;e)IsD8v9)~akVf_4@^$|U#)9hqKuqe%Q z>@K~)dX5k9T7E?!AOm;t-iEc1t*Z>kH@amoeD6b(mDeNMWjH%JK8L31iVA~PPxh^o z-%0{(pilXia7r-Do@sq~_QAkxqw(opP|||`;_IJ_hxca-br_MPlxgE(8T%uC58Pa; z*c{geYYlJb54zw+9gI&uHHwN6HoZ#a5Z$7c%0I6q!@@?qiH(&)jvOfEsIIfIKO19# z3m}8*=4D`!ALd>Qicc))u|SHA+Z3-r9piCLsQEeI;}fXek^Vc#KEtRt4K|7A(>f^fN7x!?ej;yq8m1cZ{3j)_Sl$_r!AzO06`gv?>_8SL8u5*yCIzEYbs z@@`V_PP?^VjGeW4XtsB)>F6d6xgO-LaEJI}BDLIz75iD85ANlvrl2F|M6CpBhY*}1 zgAu>WK*v)juzR^<-`#oGHBk{4T#QhUzo+L+$fv_d!W!G%5TRzD#_mDZEjjV@G+>wci`hc*3iXnneNvqw90cDL(8S4#Vx1V59EC53LezuHbvLrE`p}dfnp~9MV z(Cc=?=d~kS)`7&N$*=Zlga3Ym4nCQjs%;rUgSNO)c4EOVW}ErPvMFR`5D$FRb}-w& z0&_2sxOwHTu?yNb3VQ0JKb{+ilYMz$_paE%4#((p5wwb0F;J;>#$l@d*Kx>AKqako zfA!*xB7q#R-O;o5EA(>{RL$1pJL*6`BC-Z{7K>e;IjFZX8lQ5$heut8nwbCX5xT|k z653mN0}AU}>7Vd}Z%|Zl*`7;$tNDaO$rl9oVB`T-bQZhCg(YTx zcTvxeB9gss9~!(`_dVO!>f#6*(wF%4M<@2UWEurW-rndyo==KeN0Oz5jnh!Vx$Fm-p_G94^42oc~2l7VcY!91Vw$7cam|@d-x5V=69Y z)t_03u%9&&Ah}@QO9x-}u5)QL8Wha{5bUnj{?uTU0FlGIKkfXl=C4|m+DLnuqMW$! zi-Iq^Zc~j`VPRnjGpd~ zkx2EvNlaBTv_V$O>Me+_-rqu>_*OJQ)Q7;p@LF~dqhd~s zNan~9`$Ctg)&r|dM)d}#G^FBZEOCZxYNL(S3X0HLGcD9NwC6B(O=E+9e^qA7>wo|( zCt&2SDi>cnzT-|D4nFQPo>Dx@J%Zl6N*bCV+N~T+7x^ zlJqmmN%^CBssyCHAi`Efkjv5r>1pTnlPKYf9d;_b)KLjNmcQ8#`3wHjUNF9ZIh=#F z_g^M;YF>Y`|ABy-154W8GNRab#DwT>c}0VCdxpZ5c(U2=n#hs&a!jew+uao6Jj$tx zg=-C1z(kLNzexxRY-G=7Fy>t#{A$mjMzkoje_uo0{eAtd9X5(elob^+skqh0e=@-! zAlA_w#U&0Pcr7nn7i`kF3)Bj1$Dde=*r0)P6Yb84+5ztX`@kH@nP=I zUkXe8KY4azKLz|j5#`YY>CFJu7NK>!Ck` zP{Wg$-W%s7$|HDwE=1x{_%|0E#^yp7{sRWzX^-whIEu2B=*0E2epB8>xIF|N#ETAiL7-_K{m`IAm{al zG|yDLH1z^LXH`pVfF1cDlCM+D*ieD{LkqU;mczsGcI%4|QY4OM)2R@$qhtH}ulLj# z8SR)SUjdW!jY|OzlJ#tiy&Lmxnadaasp~&qtjv!t{26<$k6~VQ_f3aOk?@szN-9Wt zZG;{oDX8G{W$CiZGy_8&)Z@^oL3+woA#}dwW;^Yxs-HNVKj`up+<9|*)`*0b-78;%bENsiW^8p7O zmim7;9f|3;@a9w5b(I}(&Gi8p#}H>QUad8TB;ys2aCI``L0!Mo(ET-2;iiDKi+;gzir#}Q28(I z#1Zo&c|E!C2tQ#-$VGoYutIiQ)BRm*8SKk@!t=%K{i`)X+s#j>0pjhCk}p?Db>lST z((G28jXLxoqAO_@iRQ&=w$97=w4>y(iJY#wQh%lwFL*eFl2ZI0(y$s~dVNHTfKdAy zRVvzC(coC>*LYt>?^J5VqNF+rmAD`or7X3gp=jBi#bM8hQBTf$^%q1p zK}6-#5Om0{OnySr?EgY;fP?>HgZw}gewB`gB~u{Gf*el~2IH4{Mg!$@=J#@_$)DV& zc58^L+ssrNkVI1i)E0{F-p*tPN4A{MQ@!hsStIQ}8_pBlD1LLc;*``8*UpWSEv}@jz6Z_@uq8FT2h0 z#mn@sN#O2I%WNc!ig|1x2p+q)H;AnEUeW~r`fpFkm&`^Yl5_}feiA*et;=T3_+LH# zDes;qUrtxGGV;pa$R=0VPJ`^J`@12D*0>=$AF1z<^779#d+WcZ}P8Fy^5Aa?>c?Xel zn!Oz@n`FYrn%^p|u+;uP7eKLO*I$qOJNozDyahqF!>BCl)U$#=e*^$;K*}ti|NRz> zn?9sIOE9Tg_k>Wdv!!S)TL520ytgX!`h&zIJFZ0vpHU zs(K1IEa_GBb_W}_Ua2w0QDS0lQ80}Hfz6P-Pi3+hIst1e-+xt52`tNh4Eojmfr;N0 zZ*aspK6yW@UTw5o*Mps7C5k|G$onP%hUu1km_0S(OLCp*8>@r}x+i;nU{zSzq0sbP zJJ%I?BYJU}Su2hv7u>f=!#ozaRF>VS@hP6#u9`wQoK-`k@kZV5SYUIoOF}RxIpH&& z3`3T1`V*F|hsF(|G#e&UB6MT4e{kJ=`FByI;&=Gl9?OTDN`h zlKXu`Y9p=9+Z5k+Sov1?I+Vt9c2joQ*Kh;=QbKRZ03HJVjc2b#7iNn#71 zXns~RL0C~PFOb^#X{;EMFM*sJx&!F5Yy%n0R2uzoD-TLo>_ z^GeO3Y_=@h8K9A|=t5r+!o!>p(t|IHM)%}^zRAs_y!MVsP%k!GnjRWYHbgJxt)dU5i1yCq|;>3zN6|J zhD7~g@E*oumeGAfrC_cvqu5LD&IN^+s->~u(843PR`8lE6jLZ2wZzFlLl}?$J*_Qz z(A4+z<996MAdz4^?SoMhb> zci-{O`@3pOLB{u33U2#<_o2~2MZLuRW<>);3nU`LQ**B~L2fCETH>NNcGG zIqI`Bp2lmVTnFpG+M=rPC>82adirVbf6|{WU|tUMltc@DI$VjkZy{>5MjzU@hHbWE zKU!~xK6;Karby&XzUO0VJVv`cs*&=zbcoG3$xS76f6BW{%)PoBB7lMEI=EC|} zt=yg?=;!Xn+s(fwsE4zCuMS1z!>l$M$ONA$Q2h!i_a=xknlbHC5$s2UgDe{DM>IeG zs*kacnA$bdp9v;@24!-Mg(9AAGtb_15p(TafN*J096}N+k`cw5!3rkRud5Q5R>X7l z?NDu6gw5A*1-bQVpAEBq=2D)rMe>jHeIo#^E;jgq zgD%q6Dx51+=>ek5p2GPBC~ePBQj=&Kx<9x=Vp5xAP7Rrux7_U)ur|B8ppl$N#)%Zf z;|sMCl&S529l#_ZLH{H?QgwaZZ*nxsidkkS%Thx3v?-&h-c^{P=0g|^hK4@Z$5U(;vEP0&=@zP>;p_msrKZL4aMDW0 zb#>_sTlh#%8lV}1s&_i8wcMC|C_SZuR$tUKL$Et~j((8|A&@k}N9{iEyzRcD;9nBA zD-X|pw@tvnDd2B6WIM0Y8rigjd(mJwN5aeVyI2K+4s9c*f9&{z-T2tNwesFr<|v`` z_juM7|1SW;SkAyEYuZlVl81cn>h7wj&0h zIfMQcN?h^#&lCdA&#BFdMREd3N7tT3g(Y3Z+(whBv2Wkp+BGS`cqlZW)oP$cC#06_ z0-HmyC8Ss=^GxP%i4pCihZB|3nO^^dZjIxJ*_Bu+Qh8`R6?b=~ z{)^qU)ga=uOxjxgzcPyKu?kfvEWc1{IF=l23t+T{$6;!wcO(zjKP0nP;8=ge5^!WF zK4g9q_}nYs?uUhA1$4wsK-mi_1+?j*vYvO0thqEJ`p~~dXq;{#NKOQ!mm>t!NS1q> zyKUb+qMIz$;{&Ox_k6CUTahf+Bq(o#;|3_spC8z~E*0OOpTE+^-~Y9Jy`TgQA`n1u zG7Use4p$rKr-!8&%~njM7L-n7dy!mh>Tmu(lLvxemwj0DZM1{L&2uHKw6mjj=kodD zptc6oLI3>nq|g5HXpXV5;RAzGo2A6*d?+VU7EoTcktfZ%DVp?*o=ep^C~AI;b-b0j z@vmt?Usp;5B{PoTfoA)tq(r&Ot0~y~!Fk!~6Yu_h#zcB+u97Cvu5-_^I%&J7z3Lkf zL-*rn{YwW;6m=`V(=$w+Rrpe!4YR1}d0&yWc`gOIu}cRWso)7Ck+|dUFjF5c=3A%| z)c=S$3w`~y)95ur%CwOMUc3Y-B-Ot3VRP16?`CUqaKrSR&)I2e+QA@Ip5GtJ^u>U( z85k^)Gif!V>g(-av5SSyf@<4+Gu)*8jyix`%u2JWyEj*w?(gsiifEKpVv42m?&&Th%a85f< z9JA;48f&FlNcK6NZ`-YW!j+mFe92pR;I+)5>uduYib3je7bx!8K&{I)vX~MYS#0%l z)bQuu5Ii3t7h$~I?jo1r11Lga|ZX> zPBY8AB5>Xv8`Ra6U~BJ5(74)(ZP4bsH240}kZ`g+*;jFK(qGY7b4a^6sz`1hPo@+0 z5eN-Mh;6+7AT*ql>*rsK9A+`f8;oWN44zPE8P#164(0`Jk#T}v6qR$##z_SAy|G1a zPF#@i4ER$CW1g~Tjqz@-8>80{8rZ$JC6Pwq0KG;CXdXcPVAQHNEF2#I!Ff(_d zdH-L<1hw&~qE2&uR0H4Je-DJ^*ey&aT^BsZ91o%tjj0E?qti;2iQo<)i?POq&&X0$(3LoUWBDjr6%RvL zzN~b&nKGE8wTT9hW*+?oCI<^kL~-bqLHSZ#YN-;N`ov>_2#9EA?$N4o1lK7qTgAlxCHd-v{WpXU@Um z2{ht>lB2`tT3F`@_kGD114$C31BB!uh}*Y5u0MCH3g~}zxDbB6{E9Qk_v_=wTWOhp zm5w>zkqM&!hgzfpb@L`huf(eY=?Ll9Sb_AZN^M+9S@ysG-2e>DkUHznU>BE~-;F>@ z>TI&&S9%!S%dczbE01Jcy}^O)xZ5jrju-)@j}3Ow!U8AFhsA?~XR!&})a-xcZAue$ zTP`n;t#`X%KkY5e`TX{VY10Ev?>0J4;m5T?W~obEr+rP%GB(lD<{yjo!)?CsYxu0Y zU8`cRCqhC+e~ov15b#Rl_$8e-69PhQo6g|&GUQzpN;FB``ml4HM3^Ty!%@l#_r2* zIE8TWYsR*c9CoA+e=b+sE)K~Nee|DVA;o8a=J|CEB=o(5&)z2Cq6%U@S;OKT-X_b7 zwQHJOo}l+vP|Kme`@3SQ!cJdCjDGoMZcXPDR*j!& zxcCCco-Ya4CY7*4QG!8NX*GJBdg4v}xu2?JAH4CFV}^9NPtNxunu2zSe7fv5uTOfA zo&DbbmgatPC=ESV+Zp$Gxv1jBvPZwF(4O_6$JJ^-Zd3yLayUTb=MF@=lH;n3fw^_p zWAV}!JxBPp#&bcE!m%HdFgsrV>#!T^B9ff{s{x-T#NrD}6@Z=8Y}ZP~dF3EygNK0P z-N~!PSKh}RZw^J~BL5ELRO!Qj^jxsbNRZA&7p+~92`sP#Xf?i6%8tqqEF$1N0ZU2v z0{AJeB2wClPe!;1^i|1;Sa@X1yoR}e0k8J1PQLMG!=~ds2z__FiY62Pb8{3SoSQkOjg4^tlezfB?k(0)-s89 z=1y@?w;(9xs}p~(pm@)V0CZ--)9SB}Td_v~+ysartm{}Pn}yE=N$85{aiVxNM2GC- zMWLACxijN$M%=Lv(F_>)+z_CJ;O?>s>m9Sa21@mMrt}^ zPGJV}HT{#EwAgJj%xQMzb^7UXq*-;gTV|`Rh(CXoh6CfJi0)dAuq-9T&6d$1ZKi3v)?MQVgIfaL`lN{b2!6%u!q8MIrRPZ`^hn)JAcnA$v@OO^bS=M%Zk5sFG|7sp9 zotR`I6u}*b&G&@jA6^%_QF$KNp?N z;ILp|^wzNt3iAmOI!9&wt4h8z|LE^j4(||8-L*MH1Eff%peL>Dcr&v0Y#iO^ z8pllj@_GmF)r{CyEoq^WSj(0<!`!h;_IZ;G&- zWm(}<#l?izsfY?Ljx_`0^mKk0)5T*`7RaU1220v+4$&s`lKyC&+I8VA_VLiLP*T)6 zU@7Y@H7Enr0<`Nm8GOX@@~5y~isCd~G$Ma@)+U3hBc}wTbXwr%HMHI?-O!2)SO3@3 zi2W(&IG<551=dNg(M2>B)u)GazG|1;^!$xj+A%fppnwuk?I73No>b%H+>@Hu4%}Sr zi64?B^Z57aLyp0-*uVqB^908wI?3Z*4YS5>x#^#6xY4z?XkM2E&6b1Z%SSiniKW4( zZX0pN$(xsCmJ|iR}k%LC} zD1aNP>c+2m^N3|x`|M0!Canm6?p0xK)d#YFJv5F!qr!x|K^`IgS&jdrP3x9r!d821BhduDae zBh#mxK;!~HFCma<+xrnpVWHFWaBpz*BJ=k;PW*&qSXsD~8~66uJ>)%7-QY)0v$rbN z{Ay}}AkQiKh2F|Y>HOPOPgl>?oj(18TX@k+7{#;F(xD44<-lYDckGT4+xTn$+ng)* zdpg|*V&PLf^J4nzdK+jPBn)CCQ_HHfPFrVGHs54^Wwfog z*PCxe#J7SYDo<+>&L!HY(wUz{14zK#O$cfS2%@E)X=}+UEF?#O=^k~KHrdkO=u=_8 z%uw#Qh!bvEhY4gGFVeB~Lp6(7tz`sbm+2zy?w)|pWF}LSV^HLxs{=7?+is7*(Kj7? zXfltd&WUWDv;YpkK^X>?v60Q8qStdD^EqiqR1KlP@T_f-%u6o4AbJ45L;O|x{t~J{ zWmzBz3)f6f4?2EUZqgFQ!$Z+&{%&r({}pQb%UbU2Qm0Lv3tQgf;ngW7bJ$W`iH zk*HZ0H?lq;QZ`iS(0RN7|M$8FT&-ZT7_~ct@^6kURLj>t@Fsw6^B~+HT-=a4_h2+r z$EX+3**~opQ_bxR|1DByrU1D4c(;%yCYA~ETGrQN?51{ug@1m*LD{I3((lLuj<9-( z&@D{p|LfnKyAmxdI2yH?o-L%&KK>HKoe)WV>)n*|@<|15H$%vRd;`rboo*9U+_pDf z-+Zwky#2v0`>_-9Y9Ma_P2~8b`m!sQ$~0awUXASH%YIJKX7vXX$yT0jwmr2gSKLxC{SyWd9D`#aEtQ|9 z@I#dS;B(Z(5#NA&sG`wKwaj!hZMbLS70UgiumKrvrbZx)qP7wwtEy6me!- zlrR3n4hFgV8Hj#lu8+{RC(xe z0ojhX=Pb6$U1anQvvo~Ug1c9W1Stq`u~6rAur!ERmf`=LBjY~)W4DM9uD((J-%H<$ zjrdk8IXn`Pj8+5YaQ^tJ^Fixm7g{@P!N(#un~;>vHmxBugqtY6tn%mjUvZYczQxJd z4)ooUgXtD~m^&rEe+koZ;8RUBvKCq?2!TsRh9+w0V{K9H+jREUt3?HMjR}ACEBoE4 zp011C+s$pzyjlw%V!gC0{cIh&;Er_#Q(1}yk{xuPfRjVl8?a~g5490h?B_Sbw`eC% z{grxw@2NnS&hfJc_w~#lcvovd=@ba~#Q;}C57=_WOkEk!0tKunhf|A>FgINbdS7^W zTkvwLL>xIJ+rBCmrzx=}UJC^S@(`Xr(28@HqI_t#0TqTU07uEQLFhtjYq-pGS7s7y zUD8>ILZ93O*fXqzsM(PVF~Y@+6D)cn6&D2s39%Rm>eUZRSQLE=4aM*myWD-nXQ*&c zmoD5kI5H0L%iHSwo1^m|9*1f%>I;8OEBppYFFc=;RLJvR^V1#UV#DKptX^s9Z%wU| z-TCUc5!N!1l5Q$`12O}mM z%&%R!qmI4bs8lZBIZFjH2;bs8JP>~-MaHhw`m=y2LA7-*KblP%rT_;6KOcu2WKKC! zRj~f!M79a;GrTi@-Y{)@V+b`l0)1U_?Ruw-r`8*4z*(+svToGSwl%fv^VCJk)6p=$ z$+~+$N;b-z&H7!%{|C?BLT?owp0t#g3Q^^*)uB6V)ascuWxbXb zB1oIs8Vr$X;~ZM3sITdHYm8~Xgd%j+(=I_@7Jhi2n=g}oSo`M*qt3K5y_+O; z>hiI-w;#WXfFmEiWkp6R6l4~?OjgYD(L?e+L0fW;LjKBsvoX0(gA#M|2O$| zHW!fc0%8mwK3^LnB$y76*5p|u)HXasiWgWdN?&7qh_?P1&MPb*JXKJp+d4lC8hb3V z;|~Y((bz|L%efc&O@(v^qai^P!6nb1^fZ#kVw6J^66MfUdh@x!En2W>(L&x%X3vWY z*!92er63#8^&6j8*wH3uRR;#%Bl619+x_w$H|W)m@fAgWkv!6gM0jMsc#*8AY5IB| zuT!xQ2X!kbe!)-LKpHTA2R@@b1}#Nx?~^o9a~HqJi9*B8YfAtzLk;>=Abjp7^KALn zD}~+@KKn``tkLJ3QeOG$ef?cj{52-_hGZf+!J^F zrD8{u2@%KqN6oT2`~3dLY7?_1^`X0C1F)?vG>zYt46!e457Xf~M#><~=_i-!1oMPX zE(nE@qUDoKC7PTzHgCY>K-DK$M=9=G}6Fwnc4N2o2?f3!cw| zao}>>H`~-$qhti#l*WWMEjR#5U2d1%74660r7Gs@jou3A5IG=Q*|+2=>Yee%KcB&a z85h&HOKBF~B<#>!3Wzuff)TR=$LK z&35Cj5anTz#mVt&|CQ#fgbNK$QfHU?yf&1Fvc)_8SR(FkcLw#YIr<)(ugS?ZOk}b5 zBA`!hyYN+6k*VdIwMyddS`>U{?2@CYPt}Gil*=*)Y{L;_un3S~lX!Kvoh_wf6qb(24$JfD;NM<0cvbasbn2i{O*a(rMU{to3y z*ZL%I*3dS(_jCQ88Qsa9B-*&ZDeWq=C%+*1se-vDjuhV3_BZg{LOhapYC_HS#She% z)ZME1>>!q;MAPhF>qhw1ZW&QHYNm6B|s%hAbLaoZ6}-Q z{UmwD;1xRCk^v2m?uAR~~x zkun~^cLj6++n^xHfEq3|Q;hGtU$NVIrB9;tt%-oWGjRFDwgAggoAK8}Hp*J%M|{!n z;$zXn)Y?5Ib6HvqaKL)ie8fY=w#Q=LZ^&?E2?~IO0Lr=m-bUh-avk27y&3Tm8RLol z>zX2W^y=@3i9PEQ^YjqKAG6M9xT!9yLz ztaj=$z1NtSqWSsBu@=xZsM4G~tU?9~*Q)QC`i@-IU*GJddJkp}vu_S+pP9&t-KhBnH>JA}5I-;^I>4`j=N%`j|(hjVAFnE~za~bhSK~ehQtv= z5?x@P+kEfQoay=R)9G(2>Aw!dLU%_|M-N=r>5zk+hXLWqPh~gv&HL%rThQxgf!mHC zU~f4Ce4$&sh|>hz$oQ63J-Xq}K`M65FI(;(Rhyf6t2^OKvWziZaCw;g7a|9)^2{cV zc{Un+goJb^3)}7`G`MZ*i(GxTye(yCK#me*e56F+*{}3}T7bm8GKYt*38jn!s^gJ} zXVr%AA3xL*ml59meOv8npb7jj6fVD<*=}i9K!1hE^4?x%o#Fa>%BxT%=mu+jor*gJqwjU}fKZTJTz@agsLJ+ApO zZ!oKTg>ID}PZ^qHJ{S+5)(cC{&f5N|y*3zD*k&Q{s=><*xcDq6RfX-l!`elp*RI09cFY7b`8(3JnQ}nfVU`!UPz?aUG{X570u#L)WSDx994{pGV=PC}@)x4W?Ya9GK4PwtTd+`-KIX(AiE ztnu%OMo9vU6ukS)d<`xoC2B9@k>7tx(*^4hYXy46DjNiEjw!8E&_ovBaHSkwG%pyp z$B%rwqLmI68)wk3;LO=Pl>=rdhYA;o%_cIT^n5X_J;AZ&DRjV>R=`Dw!w2^2#E znp}cwVY_3(JSWO#N(sVEC%9nL&1-{+WG?%i+kFNW(n_UWjcjH994Io95@uQr3yu{u z&<}hgQ!r1v5va@P-9iaCol8nI+Uu{sUQVI4{}kv3%Mm2eoig z(zhYLqVkDyNbytx%yBS0(l`sl^6~sVG4FOy$P_+OiR%08Pwy#a-0%1Y{`e7|s6bz# z2~A_1bEa)j94eW~y4Bsi4`UGUzOWxni`T*nF7;k+E1`!h#(i@`-~tfH7E&q6J2x=H z4q0XGw(@`Hk!jD=oSr^nMV`X#!O(DC)+@zlYLr36$TRqP)04Z>b59GCs$(Z14W}W} zL>8zqO-%jPQ5X1C8m;Z-PlNrxa>PYFQe_#Nu9Wc^DDfn?%pAMcPhTdo{~UA8wGZj%Gm!I0x9f z#4`zM%b1`4Ym5zQ6yj^A8Coi0-n79%XD;X53R5Dr4-t*+s=S$mZY5Z+1Qgz)ebK0i z+0hA5G*-f7GvbVL4yiX?TpT1o?GK#6$xJMTg_+(xKjG)9;S}33-}u8h z`Vrx^LlMdsKX6)Be6pOfVV-aMh9#?oLA2OZZsOFxtI6T*{5k|-F1#ITzkwkyD{^1YIn2rYL5^`Em*< z{yjVxEfkcYvsgbaknkVzyc|idPam<8#JG9=E)qi)^?7oF-VA}|Kk!dNjyu+3Wnh*X zi5D7GR3w7&GnB@_pPYB2AOQ{@4!Bw>C`6~0XrMfwwZ1%(NKCDVRwovnpoYxtPwi58 zMq$!c=9@okyUS~8%q0>hOS$V}ofJIHIc<{#VRMq*3@cznZ{UsZG@GxyH!!VJ{!CV2 zg?^=#|B?Xda@5h#{w|&p&n#;Te)0OSrFj#N-^XcbkyOcIp2eYITWkHa>bB2CUE8` zX!~XL(!(8=P`T~4X+@tlJwKriLMf0Wnkv~Qc-3s{1QW{FoUF028cF0anfW)$K z!v9cK=!~jS#dfMmIZ(a`S{cD;IJbOq=oDN6+mbA5& z+1~z_LTWaz6|Me{P`m*6f<7T$k`^_@q_MkLtTU+*vUbh%p}e^B$JAHS^ysk-fLE^O zlItg6U=S8TysfZiDLjEb8tmUJpW(D?X`@bC!EFebgjVg1f(zP^Ur07b7HHJnkB|NW z3O${Js-YcA^CT#BdDaT`oa{VNY*)l0Ho{6#TR3X{d`?p z=T(ir{tjZBQ6=+$Q01EqMQ>q+0_4mME=qa^Cp>WV_}0xL z^6J5uv^~2bbhoHN@iqR1>QMt_p|ZB53iVj=DhnP}9mz2PL_&z~fE()RGX;hT_d`gs{nD0Xf{}xX_6A)dK8` za>#OQxeEo&n%jA13-m&eRF6VWvUjyVxV1?~O)tAhe%i0H@$ZOC__Se}1QK=u?I|j; z_871Xc#|D!bFjV<@Nk|J_M#GBkC78}cLurdQG*qrdSwSJ`)wfYCOx@7~#G<|1-l=LeuE+Mm$r1^WxBcQ_!QdK%-djtzH@!mq-0H zB8~N9`Kn#U{A;lqJx~`Z%b@#^DoM#rIZ?lec8W-{oFQ?HrsaqGpD*vDkjx5*WyoIz zc7)1M&E$pDni5s-lQZ9GmE3UTp1Yt|vMt7GIpxd$J{9Yc*r1a?`B%`#Y)CNfwI=Pn zmCSQ-?1X;jGt0;$!qy&~Q~6AKzEl<&X;&C7`&bcX3C;o%%u$ zd{hcZs@kZX$R8Y92-ju;Dz3cmGSaR!d`+_oU?dxrl z=Zyytd$6|EL6y4lQi5soZqj_P7J?fXZYSX2G4Y0Cgx1PkXoqsCYkwCpye;^t+@~TI zrlwayA+YdHs(0uRb{plUM9}+Vmk;M&60G&yMH2i89EBzzquT>Wfy@W$`N@lf%Sxu! zJSt4U?P{ttnTdXf+a|UydaQTbv#R44M(PBWry?4UJam?}kC3Li@F^QD5)2d#`MNWs zX}s-HLZ@tnWOK)O5v=rZX>OfD^O(phCO&bWde?dkM>S|N_^dObDSK6Diu9pLN+Slo zZwasrE*O?j9v`wRUM7;T6q@TBZD4arsZ9Il*KBSh)8jD+c1%WEPfF@Hx!kY@?@YR=NY0D8MPy}Va_nXGEqKs8kx-!K8&DHl zuPiRGn|8#v>y(P2?iXLYdn(2Rv%&2jl$F0C!GZsR8HlE>g!Up_v)mpfIBG6VQY$Fs zARr?D?N$S@MY`YL?V!&4wYU4sO+WS-lI!K-@_n%eNf!}{ z=5@%Fl11pC)YR3*Q7d5G8HhD#_MP<|&hb3IVsWrptP#=SJ@)F-^aWM-?9BaOpVj`BrtKhH%IQ7rmM&e`g9L{GKhbURxasMcM)< zx7fj82eQThFZmG|0$N@CV}yn}0sBEQ^*~o#SSS^;K+*}CS|?-JwE+BafZaG<&Fg=_ zQzCZz}A`v z0d3ExZSPZ-!19kjg!$$N)Q z_qCK7)>z5IU5jR}Bj^7ze`A?}1*grJVY1@xjf6BVy2KQg75Brvw-qTHc!`T`(iF%Af?XBoMOVikAB$3FxM?6gSPp^{>M;|iK%{DbRQ@Ik_@ zZVzRHNEt&y{DB*(SScm1Tv3DU$+=(-;onq`a$tMPYTF^5k?8WqxoV3SSpeEAoraIJ zW~N^zy$MmFfF2OkK~snX2wsObGgEeSzI3{O=VnKdZ# zD&|k{Y$2?8es|IrxhA;vg5>kCjAVAXwA;aZ?b$P>_R6L3FldR18LMbEZggGN zs3-TwGTGjgQHM*fmwoL72nl0v)-F~LO{WRc&Kj`T2Ni?MzoKJ+zwd1G)wq0ots5v8 zrg%zbeLMoz&*jVYEgMUBa$ zt01~;gx1>p{=v9Cu2o8a1{TLoAUxvFD|uRW)>Ac983RV6cf(}64{m5Fr4_=$zDPpD z=S`IZmuYpysyt658|U)&%hsDSDh0ZY>f``?~Uwshr@m$ysYip;OGP=(r;sY&@5soistmju=RuN4{9)MO5-jGZE(l};%)S2q50b45ap~ra6Uix197q* zzf-45>`3^^M&Y3GI7*r5i$bQk)F;UC$eG3{QQydUUuL{?tOc_0Le5*KAXf^%5?N%7 zfxtmXa1q~v<(G9ciI~QIU5DmdbvoPIO6Rq z(P!br;%o(Kma(2-xR$8svzee??Lgf#p^|WW8O1*uH3dXvJa2)(1C$*gacwYv zrB(d#_iAZ`H4WKEus$UYiA4@6X5-$7si|aT>t&_ZD&fWkOF3hNW;WF)`8lWUJTAUe z;rYZ3c<4_1$sx8~uNETGlfM_A3l3n3+(%|=DL0xTvpfFfDUE|U0v(LZD<%E~ZCajO zBt2<}TI2XQ9y@v(x)5{x{MOKt)6MEAgTn1tU?-sC`1*^-exW?8Ogt+UW&U>Gi9nw~ z-GZ@loh=aWQsnI}IKKOa2Opx4!K+nRbo--R6A>L93$=SZOU7UHHL2k5pY^|1tZDj* z!~>-{lAqklYWF_D_<|cYPCBNWo^397uB`C;-Obg~p;b_0ZipkL@&Fl`&ZoC;BPF55 zIYJP_JIOvORLc2RElcHSLUnbO@nN=)X>MIn9DX3Bi)KHG>8B z?1=8qUZIzI#9e$*RKZLM=rxsdL~-X2yNLLV`B@I|2>9fvy8>4vMxL;%|0&rsEQc)Z zB*3K;Q($bl=|(9_6GpAU;Rt<0H80#|E9HT%m)Wpy4>W zQC-@2YdOLA^O!RwMjzcKk@5?v&}Yzw5Zzx9f;VBh%@6MMG?3Scm&;u4R&AX)M+MSy zZ14Z%!(UXS5A=Cyke(3&ftt_pqKircamn-c1KAO11kS#cucaZAf=OMuuDeC7hODIV zB6tHVjfH1pd`t3*Np8|nQm$9)=UqoDGK&oro9*|m|K_LMlA0vdI?dHFqn@~|+@4so z?|jh2%zsj0Apb?V8>)1k63Jtkh|g9oXQ>%#UYI2=MP}mbY-8&|-+!;F;|(F36qd*9 zcsK6L$jA+Vx*A{^`N6e4cDs`bl`C$l>&s?*bNPXH^SBrP;zJ}VOq=m<^5i7R-l^Ao z)DcMVrl;%dmJ@L_LQ9?HdI+U4@iTNZShLrO^LTr|*ejpz|7wENy;7}%HR1U@c< ze21M?KkS=3J0Y)?WZ8~D+=y)r0Bk|j%VbduLUAqB_N9kh#y`u#(7tL`FQF&Z6`r{i zxpC>j8%fv2v@u4v?SsDKH3N|Zs4^b+Vba^i!?kg^jxy_MtgxE`Uh@+yd6D;=VeDF! zG)`-dX7g2eb@sbk%{w*LYwcIC%u z)~)At$-#;pH6!EORMs~&H5Xv_7ad7VQwv9sw`3-~+mvFUTJGJ)JdxhTgi?uQm8Q@G z(N_p(dAYF2WsUjj^v+RB>zvNXQFA21Xv5XVOwrC*%~fK{!kB{fUt&mK4rKzjE6@{7 zRhlpX);EnVoBv~j7rFl(OZf^spNhHfli5`hnzQ)G6L^R9f?P5sBby^{#L(a= z=wwyY)k$$Q{<%+5!07XZBojw9nNc&Cy4W)Rs!!^nSxo8^3tG!OrNX+HaDthL2d?JH(bs02u}Nd~uI)0qO~ zPVM+Zbq%t&Q#HTKvdaR85RDV-a;$Ly%}P2ooW7NSVAk+_brCATUtm}jXG9~ zHZc`+bwTb5Gc~U^&byLQ=LJ=q>NgjoTpYle#~jQFrKJTWD5iYc^|;u2B2rE3!~e|` z=NlVl+c#ineBZ3~sg1f`joDnZ)6lE4rW4dlrc96!OsYR`L4A^A&3p&aK}hz^a*6UBBAIlRq7BL4?Km^ONWN zkAa&1O&)gYyOE%$+MLskFcdQv3&OJ6##}WVU+M;`ZbunN{QBz{>8-1!a}bT)<1trs z)`t&aHrmUTjYkIg3=!w!Ojd{bOkZh>^5~r>M4EwiyNh9NjaQp;48s4J*L6kuCPe*# zBH=f!>o*nwsyhA4&-h6?Uf>wQ}>QbD*V)ijESxC{);69NmzJO8&%&%#3a?+V)u5$WSX97 zrp9&a*kgk_fdD3?rAr9K)Q^@lf9BTrnyq|nm9~$Jr*~uOWXZ`=zwru-kkFd5$EKKT zu*!66Gy}h@)khf~&HZcUf!)8Vm)h(auBjEJoG|vy2PBiUK82APleON$ZQ^u`%t#BiCz>r6lt| z8Rf~gd^oBR2;virO>ws}6G5OWK|$k%($oT97YkLw+q)`on?D-*QLxA0IVOdO+?tRkE3KCIr+@-qqi-) za_41>ar+{bBL-C#SR`;tXQGwvca~@;ZN$OFiwu$pYB*US5OL-d)vTY*Wu*%8S^_8y zELOw$3uzZJM|)TJM+X4{@^SNmLPr82rP1);Dg&Ww*D#NQpMRk}d4}Nx%6-F;`4HJF zC1zY19t=$?niJebzI}^UkSr=sI-k@LBSNzv@qkH2({CXlJ;~c<8sb!Vuu`^jHZn6b zGV}Gz-wjZ+LD$qR8AsZDWEMEAuaerN4bV!y^MQDy49w$wi(aiIQ)N3*pWm^xx@s;R zn@W6sr_WCERErl}nT`Rl0mV)eTN_H&!2`jkaEFUpq%5!k{NK^SN(aV*1pjtbyHa&p zvVY*xRn_BLl7imNN|wvxICv^e<>LErr6e)fxBI9w4qZKDS%e zpzu@C^bLqyZ?c<5Rt2n9b&X1*_i=eU3jilmMfZ!TsG`Fyi%bv2J6pB479iY}9SRy%_5ZX0(J>wm_iF+d2YOTd zEi*iL+(gdvy(w5;50Cy(^XW)2+L1^2b`9OPjXjt6U6&hDJ65&TtKBJ}^8}~N3=9In zt!H|1unVafF}(CUiB`DT!`E#jog2eH`~AsD6(AMda1&<7F2p`rnddtx7RfaR!N*sIG* zY~`l?U(0JqrBI2a)l%OqQinDA%+*0AJ0&22!e)si3O=<8lPX)CsD6?w5HAjkiRk|3 zaPmayy)NQ?gU9|y(SDWUyMWQgQdN;N=0xRPWS)(P4Q9gU8UHIhzY1dqQ(%~hP4|o7 z<)VS1_vpc2lWayfYCmgA-ZDV;ESULc{f4!VObKb~ls9FiB^KBx<0T|q(u)$!qObbA zT3O3}ziHLtUDfi*!nACD>BwJ@mYdazOe-u5rKjm?(ef2F%`HfiS4w47)hYtsww&qd z@VpM31*OO=2HLKWup$5l1TNmt4Ra91GJ-2!ajhK}3^oAKI$cxL=ot2WamDidQ?I>q4eGbw^{AfxLn z!0&GnWaB^2ebg*%Sg!-_kfp4SWqpv)U@(7AM5mTPeB_+Rvk@jDMmLds(nv zqH#WDcM13+_YH$6)_Q)^9e!|VYU9+Jogfq?Z0voWoxffC@-23HQFEv!u9Ck;ZR~P4 z{O4aTScvrh+!;X^0zB5f0&HaHERN)`q)j>;6#5$jbS(>pRT&w-l*nlgV0mse-(b@t~eY5uLSp#||x|~RhFmL0z7DAJ_C=o42 zT|5S4!afhD{P3?Ct+q!qXB3WfnpZCF1klaQ)DS!>9?5AEeW@9SCO#83|6m-=Iqo%A z_gRl(USA)#pIWkI$2LXl(b5VZFbP8*m_nX=!UClM&h`Q~X z&1WO!Fo#@7;njy`74=;x*iRH4hR>Ri?67OwMV4rsgE>P#v6B?1ttJB|X4lt_6U|Bb z$)5u5_E08|ip5BL1!_2dwjAjQkn@uJum_63)>@4PFGyA=(%Sm+)l7p@baeuNscQT5 z5b%5eBsr4|4tPNVnE{)d|3G-MH*o6#iXu>LS>lOavo?o{hZ&n zb%xWP1kX#SFxRX>VW~k`6G_>rE*gzUvC|B>v^W09UukjOrle`=#SnfV0YDf|3NS_Z zmGCwzg_eaKrET|x*pVKXOrVSSX_IhzKOgd;faeK5_3mt0u*-&m z_3E;pf`C^9)eS=RpiQ2(kTVI6p5|?*22BG9+Mzd5LpoBRul!hp>@vp65;2VoVLfKV zhHL1v_{)e;nK~{*m6c^VZ$+L|QdHjk(PS124+_4Pl0?`Z&pH`-Wij#|!mF0+c_N7j zA2v8@#1Kk_E8AOTCsw}3n(gK%)#@43WE{E_MnFwLgjE_wnP9r^@)b%^X6jIcLqAdq zRF6U;0NMx093Ix5`>H+4qDB=Zv!cbI^T=}^pIDxko?rsL3c1Kmj5Ot11aU_jx`|LR zwpF>%G3%l^1yKBSNJR}XVErUYT1c)sZC*|qY z>97v0dvU(8<$U@PwByrM@AUq_LXxc-jMY1Y8K}- z+x7;GZN%vo$vgtt<12A#+~~5;?ak74yGDK27VxeOnr0Qu-yenUCtEcR<8*YPrHjm# zQ6%^sct2hJ{S`^M{MJ9vI^`9}`{>P^Y_AC8+a7OWNWC#>w&;QZKiI68I?{ zmJ}~`H$)$=Z+r#DP=b@{VmlYwKCsBpC2*q>5*mM3nJ6k(92rj5K0CXxVt!)ZMdepQ z3(g~#&Q_PmBVQCeI;#rm0IAK0bex=>lIW!GHwVSg%n@EQf^}JRV1ilQdSk|of)|QS zc3d2AuK@nP0*`&hZ#?Im=5hjV+fwWwWGI1^{|gsEM)PWDV(xVM-P8+~_4GUWGBN;C zo8?rlT>y5Gl7hWC4k`eS4GEwt<6EIl-mRChr(WiN1MmI`J*9KG$a#&a>dLF>QQbO~ z6<_v0e$3`=`)&Vtyx5}6QbXc9whF7ccm+0QW2lbf56|^G93~6zN*aT00xBhn6GmQN z_6;UjTs5$LDH+pr-bP!#@WDd*X8AF$I+B&9nJ zW)$#?jK6l^hYyrgrvk0G2D{AKM!W z!DU|d7!~)|uiR)A~10?V!B}zQSQEZ-7yZtm5bA3qu^qQs>nZ%_!E+ z>^;X$;|>hhn}@%Zo=f~UwR6w1F0#_e-ti&hB+08i`SGq3rq$AV^@vhhUAE8>xCh!4 zO^A&#`(8~-%U+r>{3O~{1VckS=i7eO2lEaT(}kQ*>#p#qm(g>ANm&Y72CA<)TZ zwh;NK7Qyd(6|KYN^T9G@yT<>x(wayAh}0YAQA4QUw-3`Ktzt6z zpGVg1N`;Iy?997LM5W=8l#K7KsK%gAKR`MS~i_ zkGbcvapjeQk#l7y+ZhSKY@3%921^`@W%Jbw{H$1sIBrLw9C+fSp;*7qY-uu zIMR{D=$k!rWq*gRA@^&cHx8O6a#8qbK9`Dx0we{0Is+M=zR1}o*E;cNOk2~_PpYZq zQPA{xEyk|FRQfB*Ra$r*Yx*v31xFX!OqM3620d{_vOUeutqT@l?mRGrc zv7br@*c&Iq&Y8u&usZcNOcNzm_X|d~t3hKnweVeFFXAQSkT) zc}hQ5Rp}o+*m1?U{C#k$@;}8kl5KeJb0v86aE3(d^`^(es9ynU5VL88$Z}k9^L(P` z^d9%6i}~5nUezygT^oDjE%tby{56L#-#G%o3|YEbE!jj9YpDW*45|MEKAghKhjhuM z|B|v@@GceEa&)jFhz?4p83WI1yNjw(Lg4_(Yi&cYGj3hcm$sq6$lX^2ZlTU*tvzv} z_S)@wWeC`D3j4MVr*XuNTIi|0UnU1o=;@qw)ECA0m#n*w7!q$tn87a-35(8m@u3aN zw_Dhw3r(RvPaUjDXUoSWD_JzP_}?ztQ<$0U`Jj1!iEa72#PcNqHKc{CQDD+>E)bN* zp*Y=g_yxU=lBq@~V3FILCL$Ck`zC7Vu<`njld()?$SUdN=(p}TDVV8a7TM>Z;N zJSRGW-_lLG{nE(d;-uT`pkV|=Rp+rz(}g;|si`;?)`R>0w&`M>aDN=jZO92s@0{iQ zBqxPBJ@cnl1&UuMn&Qd$i~;L^_Oaniwc2~G+uD1SNpO?bt3#mCP3r$qVc>+Be9EQg zM1iNk5PX;y&x>f(C&5zhvohyJMnEez!pV>hlib&gbdA1OgGl@}DvtqCLR6T6G=L}80Q@!OrR-g zz&nBj<2~9ODGJ_Z9514?1u$<YlQY1iU(;lz_ z#@)OkzTWIaDgjV5f`Xm6I!$u&r$7xV+qZhgfJs6R=arOjW)kO!&@)3!IzKR@bFItm!5o9 zF1_>RtTd2qD%kF&^VJDhcv^NpSWH&%pdNWndwj3-s)W}3)!*3fm=s%N3-eWeYnaK% zyN&3mnJ$5l3k$eqbJ`@L#1ug-)5JwAP!ml*)V*ncf-^RFHB%{&r!gvip-<{t5ofyF zMzCayk>hAEe%E?vm3;GI1P{A$Ik7toKLsq47(XJYsv(W&#IO!uuOSW%;M*QD4^tL~ z|38|pGAygEYf3jrOLuomcXv0^(%m54or03mNS8E7cS%ckNw?IuectOkKm38f#eL2` zd#^P!YsLz54%wW{ETz|2C;nG-#IvdA+ zdrvcS8qg?bOc?!YupQ0Ci(_-H@kdO*>G;;A7W=*X&EH<(L||j&OG3;i^%RFpV7|P8 zhTK3>$tbv-ATaT}D#B6z7BjEfay_{!s^h{IvPy5L_TA}}cHrE&%xM808nsKhNE;qQ zKyz!~xW0S;gC6vl6fLJ>v&}LWb3=5cuOb9wpyvnbVZc3e)PMX}*<6%P_XhG3O1%qliK3yWS(Wo}^wIJ^^ZBQ|2vrT7?Wtv%lArIo>m( zF%G(vRN2PJ_H3g2pUF!+MFYG%nEjfxVm~$Fv;E+~f1%w&Z9-C&k;uqEa~})5dW`h$ z#lx^h?aiB$-$#oo{G7CfHf+6lVMR-a9v~DIRYLRf{`@w=yt(||+nD?lzgy)lJXLb| z?#86B(Q>dr-*Dk@xaCkA-HZR*(E9KB|g!(Uv9S zw0*~5w`ja~(nJB|A;I|~5)z3GoGc-5=`&pcFzDzgvs{(61v6q-=3bY~2P=p#w}lyn z70alTionX^KN@3}12D`0{jhHp>J32khg3Wn@{9!_k2J>c9=&gUyCIt>OLZh zq3WAaK9ep`J^X#shxDsN(S`Ba3a*@c#&QXjxb4IvpV361bBm~Rts`2gmTB5{mmM?m zHDRe9ZR3LWeRlWXSN|M@D)yu|_x_a!LX9lilxp&;dEp{OK0W=LQR&|?%DziLdU4M6 zYiK1IPthix1sm#aaUpJzNTN>$H3uAA9OW`u%EaIrK1khQ59`IWkO`rKP1O1lltCk- zTmaUo)e~>rGWQ$t`o3{>M%MP$A%~XGO1URLn}O8|U zZp8B^N5$Q6*l6f(7JF^VWywQCKH=KN0q=0P zX{oWwdz<@mSE-|K0g)Oe(H}PFkKDc%%ShfC!((A%8V6JCDN0NE^<~MGge}TMBJ+!3 zIYQVr>h#;-NE&Nhq3buw^dAOB+CW51J6*3FO)&*1WIUU6QTXrkNvQs`L^7#=0Ps&H zfNB}_uqMWNN-n$M+KwB3;=gA!co09)YdEO!+oipCM-sRY^1JAuC4afr_p(F0w(>Rb zq==IE<)(r)eGS~1Jk8k48f-K*_dh&)>v!&5U^`+uCTx8p3$XCIGP26tdXUoW=bBZA zahNn&pl_01`Rtun3XLe2_mk=rHyz=w*d<}HdW8bo@7vVo9dcQOqc|Cv6X85k6+Vo( zZ*-&Vi8J4pJf-40!2UZ3-+HZB)+C-P^pwuk(*@w}Qx%!QZaz5|gM@FFV9_v;k;bUA zVZQOxMftG3Wt)0YADCw1sHb@XIlwjzyV2wA=pD~OoFMOEN ziB&7kEdxHwz_-$OC$tldC8DWR|N5I3m;V|Z%r9x_SvY{b8X4gP8z@_*vOPLW;rCRW zJ@k5WK^s;Xr%M=GIn1m+8A=hOoE$K;CRP%1?Z%>QsOhJNv~DstLDI4-=}!Ivgf3U( zGXKy5KQFv);}g^)qIgmudzeh6dpP)BE#T}7;o`zgXyN{envf88@(X4+|Ct2%Uf$_x ze_&5Y$u^y^MA+kirm9tJF_8to=EHyplG;^CvDEI57~lY-=Dm{yW#DbW_AT*kbXGip zY|3C>1OYQpD4ASBiIwH3zo{=4$&D9FWBy-zqoksF4^TMp$yz#WN;hD}%pBQyvu?<}V)x@2aRVBSu{7Ozy!Y&Jih7j zC*x9=uscfBV6`b(08y>oeLTlWEL|UKp5acgazWyCgK71Jyj5@hOlB~|AfK|@7$8787KX1T>C}hndS=ebTPFT6i>@aA+>q4_B<*60=jL4ZkTRnU?V}ReO?u zgdwkwsY=kduK#Ip8(Xq0hhEi5PlXY&QH-7zpA3>$=b(`G-Vfivg0De}X-|fUx(%mt z6?%H}?KX6TVk94-RwQynDJ$8|ds>kxZO>c9NF3Ml6ob33_&D;B;LjL6n8v$4-WS@{ z3(=D-hp2@3>mI&Fw3!~4zq#aTYqDa<>PxRc=p*(m6DZ4k>1d}e=CnNk;L&e~I$b1B z#5KnoEEj;iv>Uc^b#nz6&CA(`fRApY{_g%O9Mo7CW}?-~k=!1Z2sF)qAcyFJpG=)Q zDoe2z)}rOkHIM}T<{(FeV_4EC5M#N%7Mzi+NLRyz6zOG^RePL8W9pA$9W07Pb}NR% zK1Wg}4~VeBXYyp~)DMhAqFYGwR`f5CN7YIt>VA#sN`b1E3Zl=|DM1qs@|DE=xXew# z(nT1jRN}Iq?cLX(z4FDuVji|ffm=_qh}buRp2e>j>*cx5Njty+e}!`sOw?Jr{$oHb zXNvdQ?~JevTQ%5y-0<{HWCwmlL&9b+f~?kfOm`#9gvG&q+^y6s$fUug6qFCokmXH3 z+pELMO>G1WIN_P`sPSP*-0&+P{>Qy^RM}~0U|A1RCe0%5&&vfD&QIBBg82(dM#ji- z51ZjU!+zbTr`eR)mCp1Pt!cM5FEt`b01XKo9vT5_(;{oD-Xznx7J^kNV&Oxf{H^zdZF_;ObTj1IPTF#{oa|fTuT=W+l(E}X#sJf z5DA!ZGdtgK0X$gB(9oNO4e&P4z z0eH@WEoP615yT!YjtZV-@zdqiJJK+cIM@W~ULckPWKLO`kXx%BbKb#>D*PLN1Gp|b z%1T>4Og*&CU9PL8#HQ>Y)7Dm8G}aNb5=*UfeY0i5plo1hoj=L)9Ts_hC8S*FoD09bHbq{mUCMB!y{Dgo4NOekX zb%|o;cUXqsyW=bp7biPNlA9B-5%Rd3#Iv_u$HyG%Hey73R{KZyS;K?{G+=8k6@+8!?`=Ydb za4mIgj*HkGPb6hI9!)_b{f~!hu-Dgo4cftpKC{i_oYq~k^8tdPFeLUFy<5vBYzz->*QHNO#^_$-Oq?4?k!jjapP!KDUGsqz#jL ztQqM4zZT%@(7S6>zpA-FSr&uu4M}rx7T;lrUhq3eeHnUv!IerN&cR2}REid5`D#tLq_RE15X%3wg?)ZQzu1Yk_CzA^ zNakjP0Qi^lwJAoUX7n6Vo^8%BlUaP)i&ke}!NoWi1E!=|SQiaSUM5pBsIiPB-;t^h zY5puR+AL)5!}vYz8!!8DI*ON}%+|lb8tYl>@FDgh{YSJE*lMF~ZkBu|MB@1E^sds5 zX~lJ5f<#jjkvc^ul9_J0&Z9Ey^@-*)z-2*7^w0B6i;veYaY0`=Tn`tjgP$L7Qd18W znjW4`6O>nhUCdud8IY+{=x z=Lsg+$83@qD&W-@LsnLZ*#G@wX_eB)*nVg;xM;|>CR~g)PguaVU7m(ZRt)|AIfU~Z z$r&+s$~FlZ9qk6pivj%p6^LrYOid>sHwQZjRVg2~1ZbT^&rn(G&|**F##7#B+Ym?w zEjzMoEISf`1R_eHSxZWE!Vd`1tIRO#lM<`GW%Z7Yblz54tP$5qIvYjz*g?`3$sh(?{a3N;P{L2F{UCSPdR%`0V+Y5crY59dmxTs6Ug}ps1sSVquCa3w)6Cl zF;82mKQdSt@rZwQ@2yBDx|)OmUf6!OUoz0*iS&I&ylZ}M{H@yda@-~t`u)U(+e9Qc zxHw~_^^G>4_U4_T9ok+$zsCje7uH?0BSTiZcLs?^1OU{z{ClkWXZd5P!-|&sCF+2? ztj2qVZ0IuQ^ZRA;eQf0J%Jf+sW7;Gcd>*j4&N>N(2TAx3XUme~iH_GUC?*a23WVE- z9|>@0n5na;nZVF#g8Y;OyEE<23Vb}1;z!RVW&LY-+!T57^9 zRQP%Xwn)_gowuf(k&o0+?~u9h3*;%2ImAoUYxP2`8tH-1z*yy>S1)1JxZkotMP(DC z@uMtT&&9W&R4ZJQZ2uB)PDItz`~+@wxJBYZ|Jb_z*hIMpF*6juePWBXyX-TJ zfK23&ID+vN4}Azg4gIj^xH#{<0OKnrmpkOeilgES&{fFbKbSja-4FJGcv4pv7GTQn zl)6vqfxZ*)Be5;66ho5>|F|~sh|fF*xP1e$Gh`T*c*A0c&qp+-=vE^ZtQ94Helq-P z4rG}C^}K!3R8ac;m(!93^VYU)OY^Ha;n1MKE5Bd#$OOaV^t8_@_Fo=LaApJj2B1#6 z8y9eh=H|+@nyuanT*CU*BkqboRFbP7zRT>s?C4Tc+2q^rBk}L*=?OyxW>mmA2Jy6$ zzuFn?llXTTf%f-kd!Hx}?LQi!nZZWaw%_h_KZZcaeIH5qG7C&jWB;kBYI`Og&!k!1 zZC==7zR7hs+@|g1eWxGq!F0;7qYWJV(9gW!?-x`sX>UV7&~ON;X)h^ev*6E3;E8^* zEVQ*B5O*<}1}$|Gi^RzdCzfhWdGq&T(&d zf-`G1z3)`~`jeo51^c_ajtkRQAVr+V;%6c^3Q)s<+!kzDUR5dH8Q`=0E-m;o0j+SR}H))(-={PT`xOwO1!#D6l zq~Ph$z>Ac`vi%J&%=sNd*mlI6fvxjkA9VA}UokAnR1*t}Lj-87U%&hsJz@)33BKtQ z)TXscf|uDpWVfrwH)bNX5@ z1I`~1Pi3motO2wl^FPKZnU=+(r6XLny=q9-G4#l-<$(I_UmvGizqQo9qyTQH`Vp-8 ze5TVodm!+7z-DGAx2bAI4Kv=AV*m*&{hsSfWu;TUN)q03flZ3f^A-fuA*6pWT5*zH z;~TI+nQnE*uGG){>QwByFGuXhnhDfWlY+R4qM{h!yT-tvLQ0lF1k`>#b~&EZO~@>? z*CvJ6N3uV>q=X_>Byil`6F}((AYg^_M{J>|sbNsQ4^WMkBiBE~TA4V8 zozsn&|C><)6E80Ug8$ze*Ltwskoeb3ceKI96zw6+bCC-ogu6vl`v*xf$h3KIW}E8Q zk-G{KTzO2fv+o}CpHh#3!gOyU4v=&i+)UNCt6Dag0dG2=5CEO{)Q&KK63S04+VsQp zq7&ARd2u|Ze9t*gAh)c8nvJq@kR*o(U-RYWOkrS6r=Opp?r@4HHt87^S3hj_t+0jt z#?88rnf|7chGr4Km$lvA$y%pnO7d&fbXcvk5wRq=|4`QpuUQ(EiA8ZbbPPj&Hf9^Z zF4y5*9F`{H@`@*W5kC5)5$ZUtrFd0pGuQtl_Uo?ie3H2x683E|*qXx@%D2b#nfhgJN0j(MAn zC!svmjqjji4!f3U&I{-rpaSJO z@E^eX(72b*nB`yy3H#OK3+cjk*@qay^*sP|rg;zYAQ58NxrgYdNt#0&#;|T+KSqx! zf~r9U1(w=-7s+LZ8eIvEL5n1x9kn&Ep+8sD{SH>QTAWBd_YswzgaTuDJ|yy9UC^2n|1irCCDlE@PaGT7eei=+OIIzYQ)6xt-z? zEuaO;CuBXrrCk^K^k0Az`<5_Kyl^L3upL6OPY;O9F-#6NriR8qP0=X_SEQp!Bw%1Rq7A1xx4=Rp=RY^n=tiQzuu_XD6ZGmt1Cg zD1C+eu8&9c01h*GaN%DMaNKV_Mg&HDtE^%5T;2N-lU)&yAJDVgi$6#n>>*Svd{)tI zKACcmZq+N5rVM-f_GbOea5UI{y{^)U9 zV7p5Hyn`?Gi(UvH=Kjy!Sw@>R9Sk<})`@EA_mKf6e%;Qy1@U-t=O47mgly8!h$C#& zI?=?z)|RM+0~e|+Y5AJW%m&H5RA>7Iqw%Jvq2{wk3v`5L!NpGxgJ#NG@mx)hSDm6< zeQU{tT11Nqg-hM_1;tz=TdKpg2w}!omYBe`wmba;9|&b82eFW(?=*B;XO+N_3siXU zXz4^bREi;-=qiH7?|T5op09322Ye zs>HvqpSLmgV)5GH&bSOXzx1>EqGlFB2WW+6cv#7qF&LyCFwv3)ytNa>)H8Q;^#N$CdSqhr~gzg zQo!VN%o00YUjAHJ{)ab7*|NY4*H)GT{%(l3}nV96A&W zXm89cA@E452dcO>+bpqQb>A@ZMyOx`Nvph1>s{in+ty>X>0?cY_S!^;Ri&KfsD}5f zhjCmu0UBC1UfXdpV6TGcA_4zqE;~*Rnj#SC+3~#7$S=q&UY5286H+Y?dt#t)0|p!+ zr>p(13x97cr4k%OffJC546g>Q1!s6Okej{SR2wK1zy0#Xr>-v6?N}>lX+Q-X)nZrA1<43MA*_`|u`GqnZ(D-9%E@ZF9yfR_Wa&uxYAxv}T7n-eeO&2pm^ z_nC=qv|P1w`cVF!l-&LVF`xV8`R#Jjzm&V{13ub4!bOzdMZIUfnNnR^&I`Y#~ z_Zu)}^9Z*(#Faf52wDB~7a`Y9Ur9;=!%Po#rw8Ym?I_-4NfpX1=Rv7yolOZdfc}oqZ%?g4J<+~;h0O!I1_Me(& z4MbUhX@n#d{xB#_0$@y@V6X)XT&r+z59aC*tH{nsRBN|fP53c)wP&248}~-ya=4nj z@NB&pYR@*S&aNfff$=RoblLZ@^L)rEE{xy=2ii|%hpHSw-`Ld8-1)E{tfN?ux!*l{ zdfmGptZ8wQ@gtyH!lgG7Ot8RlySz44vom%qut}DnbQ^k7)tW^_easoomrj5^3atLV zb;ZaWQkIf;HB96Qggj(}hC@{L5d|}x`CaI;*)tVi66BekYc1o_B1qza?!+@B@}o58 znPSsDcYCuB@vH6w^PS%n;aOZjn6zio{grGk+5n1dFCu$5vp zg*I)jS5{eH1U65<&5RgyO1R*dH4=Ngz{9@Y8*(4VF2?mFk*ymlloy6fkd*BCIdfwo zc8{`1*ZMXEEjut6A52}Uk2K+U8SJ#iM6&V@Mal?0^-VB(Syl~o3%EADZ<=STt%Y!C zEeo`sNq(3N*g9Ab(0F!#p-5w#TpL@dS?rbFX<|WQcZ<1 z9F@eOHcYpDL5qcT5E+YXTpwoRF-=Q1_;4g)rpJ-x9^qXE60Yq~0Xs5(ANuRTh zqPx~i^JBk&*g%;s__%85m%p= zaXFBNDF#m*#m}I+AOVilwdGwLD6p8!cI7x+_n=*76pJ(iFp40F+p!1yA!Ft-XDYEh zc@8H}S11H(&!K(@y+vy9Rf*-URmYWtjW#1I=A4{|Z1cE4igP?PV})`z2s z+OuHHz%P6k+Z38riI98EV2!05u zNQ5Qp3xt;ghQK4+*bC2WbnDKyCZ2=t!Z?n_#M%gpLGJm;>jcG2WQ9x|g?dZu(1=I6 zY-uc$O+KAgRrW{kLw^;6r-A)jpZAFY$pXG?*;`+Sw-N}DMFTS(nSuN58~-P^NXJfu zy~7fg>SE0_T45ECi&jZZ#s552>yomc~L4kkrj zARzjjOK#2r&pk45bUVMaE_QZ{(QX3qD69|D61nHlnJk)IFD=~VBaD#*WJ9s*#0h%G zVm5XumK^fYch|6mV@cr4395*V!;kFF#&8MvacXh2(O4R(H4OW#N(nLH-x{M3;Q61g zF1-Z7SMyZA*IFr-2%lZH4l|B!Tbc0b6@|BwIYZlwm!{E6sP-}VsM4n5;y!1_oiD2B zv|w8@MNH65{cuKEg-=XM;w3R+iOd&qsS6oSnfZQake{xt^+E!JO|`PxOycMfkYVMT z5db|v%%Y(oW=ZUK!|+t2V{^%Ukf%s7Ja%z=nwPu`XJKB2i_cTF@q9OffaIE+VnqfI zDe8m7mli%&=SO$351b1sbj>XLqu+p+7x-fDVH2F3jPi#M9)AOimLpgwLLI}OP&Nb( zPF#6CLks~j7B6KI%wE?!=H|2uV4IlipUy<)qZL=$q?zN?o)R?s3NRWV6|4s*k_wEKX4;BU3U4mBUtx6eNrH@vMg?=2mZ|Y1fsi4?3?6TO_Up zYZbNFVcV%Cha?Cq^*U%LrtTz$k<5vJ75V3PBU+lAK=uJyw2DrtL=nccl|;KyP$)D_ zhi`hFV{Uw{nVHva8tqr^$~<>l{_O#a$NqGJ6|HJ-0gBy!QfAF}bK1QwsaUde3A7*Kcs4PQV3AeeL&@pMb!w<5hR!bXqAK ze7BB9!#O(+)r-iQ`KjjRFbncS7c#|%2)cT*A;<(Y817PXQ%t-1V3M|>#g+7O=))%RDP$#Ts}J5w zN>?IDEE7`V!fZBxEGxqo6I;4fDcigM$^5`W4QCu@El zOzP1HM#edcpdN}!;vu!HPY1n{Gzb%2@5EmyOcyPk9%+uJ5XE}9`APrx`Fw{rftM@g z%BSO6(Pon7Ifsgx6iBHeP{R0W2`*8;b(2#?_3~=XhQq6~9tp$Xlx0up}}T|Lf2?ZzH;VFo26~7!_%rw##w1LEpK?ogM;1bKxZz zieIU4@bI4Cm&fLL^MO`5RsAg!O+8~m)Tf+$cQK5-fvEy$h zTO*}@=yCoSWiKEQ0NEG8GoQ{kAz#A4@X8;Y2A5L{?RnC7vm@DS* zjbL50^zSBc!eC;*4VNn8drZIIhci8)#X>_CdAJQg56}-O@fR@t*)}rh+`_-W-wfM)+DfOk5jVerTn}};SWQG|{ z*B=`B1*BYGbQssX;%&Fn$=IIaRL=sG)?Ibm45F9guK zPn*(UZ32@jtn#_>Qq_ftu*y7<{_YSyn+1=zgnmimeyX9p*5@YzeNi*K7zNug@eZw2 zu;0{&k>I}&5QrxB;jy$Qig)=J{ToNS+K0m+KDAtFwhIoK)ZBtSgrdA@JlWbxSTVpJ zjJLL4s#^(wSs{Q96QehO!WP}Aum!{cplt8MAECLu|?qvL;;ODH(hd!HVHfP8}c z&C-%hU7ZFcHJ`20w+4EI`ks1E@%q-}@*!pU%{%+^A)=|Sf}Qiy_D7j$9eI^ z6^nE(BG!T?KZvR&fSgV%XCRlYLWAu`>2mA~FH$Z|aRmhwoRHz6r?9h5 zB=9ia0pU!Fw$bqI^P6@fI-=X32+b{+oTZ!aEfXGZMtIba;6svHqqwxga^coO*@VY9LK=T__ z`nUwT8YGBIXA zJ-EN7V-(W&SMXfj_uL&~Eo2c#RkGP4f24BG@)_uQhWc3?EBMsxNtfmTrt#SDm zcPm?~uwk%Zemc=o#J$C^VbMUOLPD!H zn_XF$rso35!o_Dsp`w*VzfN|7UOW0jm>l}^=E>eXU{e7ra9(Mo8C@?gqW&}sw64*iBD9ES=dj$tDG)&VPmT;nPI-DDrFPq(i3D3mFw6|3%w(l`d-ctCEy3h7L0~w zvyn=jwClj#S7!d32tHvQ%^ht_dZb;~Q!Jm2eX3fGpQdR}3d%fj%B?E=>iSEokG z+mf7^h$P{Io7VlEiPc@`=?Cn`m{!IETa)sKcjAiOokTUU3Mf)<^JG&HfjTt=cbeyQoK~+a{Tu7LM|Ong`ujevc&y37Pz|6PERLis>PXK8F@L^nUApDI(S{9N)+Uz z`7YG(-@y}Yf1PIjQL7xDoMkY)Si2NUM9|xICIxzK5MBNh!~I(uZ&j~{0Ihpbc_W2{ zjGC~uu~Z9=qex8DMTQB7P*+;&aF@z+*Az|?7$85-i;3*-{N`K z_+h>`V7>gzzz((a**!6vH=>lpAclI={kwA_dwR?aU1Cnv=JOqejEoZyB`3Z9LVT4o zkDRqSKkz-z7hO zOn&cvSP89ceJi=>|JL6CSxPXr1CH~nJnZsdI);7t z`n&3#n96!kQ*k0x_fAQ53^9*>H2mxE??_9ajXF$2q$2Y{8mBmR^$j6r5D$&!PH!lJD8UE_T9MnctqW%41SDqMPE5HFyrRWUAso+ z{>VGYl-;*gaQv{|J(s}=yTz2Wvi{`o!-B~8HVFI4--Tea*qCpC%gn1l2wCYgd}iCU z|AJ|3u|86h=0`I4wStO|>IT+kH^Y^&A8ufbE}kr5AR%FK1+ZZzE166OwLe@LeGD4u zTG5k`07dSTEUZh<*dh)wiGN{imR4R5U_&*rvzx_gRXqqi|r$kXQ7p;_OZW4C0VMY+%qA0f% z0DB-8ex~AZgLU_xm9qU1GOP>WXDa``S;9T?=Qu~Y_tMc6>m?L`Hy4dHLQWG z1+V#a7UnkOh+(tH9R7aPKdn{g+P!h8l~E~Zhr|_PQ)(oFDrhl1o<${8p`qE?IsKlT z-+6o61c$7aYLGwP9b3&;wEyN|Hm^c0y3`ok`eNHjDx#5!86n=ipBqtU85hN7b_vul z@M%ZC-@+Q9yKikAwiU(|li+k$SkxS|R;(Zwz>1B+`s=~Ph#)q~j+us0r7fgx^-we( zM}6-EsVMDip_9Wl>pHfj1be8EJ;g(p?WA){Og^u4hJxQgB_$-ZZm-^xhflzz6Y z_Y8ELFTVBifi}&H$_BND$DkutYWlfxjQ%I;F;&_;$91*#HDtil1P!P3mKiR~o~;!L z@d`t=iuf?MU!nNjV)li}+a}wH(b3AH${PPYl{8NUz|+^@89LU0&M;uU2Q({0hOLWM z>n}$r9J4kmI@p@AOn^m1uQ-~F{S1?_5nQAAg4ZoTY+ZGsz_Ht zkOW0<>)x3O#H2(fEPGu0oeuibe16eI^Lp z#Km;aSSK@9lpc&yC*H+O-_+UUEY|_w-)Z-g0T_BX1Pb+2(0(KXbs4@#TX1zJq9s5$fgO_NA02BF8@kwJ7jztY+VuhZnwYE)j09M@GTy z#^2}yqX2k#x!X5#mRwyg_(QhU7UG|r752#pNIp4>$HN1dOKCU zzK(c}N@FMZMwl^_ilFFScd`4%NyIm4TLY;e3g2G{zu?|lUVmy&i&apR{uUUH!Vtu9 zd

-&6X)>x9(s(j?Zz-O|^mNAQsC&!_<`A>?C+|q;ShbH3Y&-T-(evjVjqN)QS!sxDvgf6KeHqyBKJd!KSQ z??3o;_GD$@4-Vg8$vtQHe(IZ@aUKpYK)e+zAQXv)Aex%`8Hbuqb!UIt+>oXFRHJL? zb)>|qtvpksrlKND36WW!#i&oroPgA*X2`Uk+#)bCiaqufdngnk$=ve0_hFIU-`h&Q z3)TGz?qUVm-QDzp4BnZMuUyploTbJ?iR7@zw4Fi=*X#?F4-ayd6Afyr-!_0V?sJMn zjyCitx0p5W$~;ss6pMGH_H`Y{J}c(Jr^zE>qIO@(A7buA#W994r5eeL6buY0pi?$o zX|_TonZNuA1tTGGzjQuU8bQ`!e5ZPEjqvo5IhKI#(+eaZ2PnR-^bIH5b*}Jbe)0W` z;TYBT9qoLn#>_Me_zdHRg^kQesS5QU22&kx4pL2V!JHn@jh8UHXAJiDP#kBtI&pon zX)2O5hsrG}9-0-tQ3+i*y1*G>d9WIi%@In3|U|XeTjr<`A>wC0+qv zaC)ysSdwDv5DGg$cfmbgx#j50uuKKxW75}WH+m)%F-+xvO3#xYKXb`Zlj`S_KdWHg zh}#&7tvS29qK4&(h~(KPfBAh!JtbqdJI+(!_3S=0s(x`fDt81knCog#K^3es8b*MN z9lUjYwuJ>~1ytwp11Dan^6k($ygovi{dfxcgPHy7bh&H~9Ae#3Q0lH2@yP8Ksiy#H z?K`n*sALS}{b30yK%Coev|w+Jc>P>X0imP1SHqDn+r^NHl$I(B%RkD~{rUOV@3Jw} zABZ*D!K!dKTi-0|Qa8|X$++zF$A1|p7D0S;0(+l(OKHxj-Rgjfc1B=`V(4|ebdXG za|egr>c%oOj2x!GC8{>`(SZ=`!gO3-zPo>=3(&3C+OzDJV+ncl3w-ZvB6V>kb?S)* zKEd*%$!8-5leQ4kVSQ{JgV{`Fin^}VgZZWv2_G(knQ{FVFZvx;Bqp|AftpL;ICElt zZWBo$VniV{3R18(Nobp6@Hwdpy>r^GYXfaaPE;jAdOry}`~L3PC!X<4?WsapD(3XS z@nU0;j?QAYP+Oq3VP!<@yy+Yo-r90pMZR)MzT$9*pg}J?&XCDtpnq^&D3r6^A6)^puu`yED)kMdDhia3Vpjdx~C7BGoE9tpI+NhK^wsPc!k&pt{ zUO1TR>AyY{HMc0k4`?Xl81GoBYw0X&lnO->Y6GaoScL zs98R?v-ce=;|HlHh-4M(>&lw5cYfDUZq^Xlnc6YO-$>y@GlLO+=@0$DR?*R=J_~zD z8j%C0FJbH^Vw5(GL;Ppvz*#sfV_fs@&X(Q#@K;eR3=-v|m-(Bx=GUU-c*SDX{zWXS*r{ zNdQHWFt5Bn*deb1kC632^t2Ml4vK$$;Ryw-_q+E~5hyUY zZs+&b@;{^0zuIN48sW_YL3#b9rW|6uj=<0*qtb*|BF z#LUJ`H7V_zQxZz5V#9%~vYPxWyP@F=7yCf~kYJz%FUO&Ers3 zwk+r{DuCU!I1P^@_+YL)6rBQ*h3_LK^rixNAGQmx*b@>Lvb-tUs{sjg=v7W@YnV~+ z8xs=;F#3`U$`3rwQtrV7+lRLBfsa;PPU>(OZHPk82*jO+KDAKa!bKq6spD}!ZryrK zjqEbv;dO0Xz`rMilq(t{a5PU&-62T7qJXis8(x8fU-`VU{R^&Hu;waJgW~lBZHOr~ zw3(PiB0}s=>(`oXjCq;2Ry9nK8vCUt{lvB3a2%+G*aJi>aoE1J)25Nb!0i8k)pv(D z(9}cSEs@KOgbxZSQ~6U+=s-ddeLhG+y*JVLtI7}-9ewxb+!wA&zS_9_5%wHMFP6m- z5U81gyzuCGZEG{q`H9c}fhsXI74h$#a6K+Xw9`T2=O6a=?+Fo6iD!Wx^xEED{w*mT zPI0@8cT*Dbil$t5M7@bx?~JPz*qzG7aRTm>woIuk>v0p{*xA2#-*g|R88i@kqp`bu z(-fB}gTq!D8cPW!DDo(Elj%W8*pIykpMkMna$=Wn#f&8Pl5BTCUx6epid3VL8*wfY z!-xTV;mPV|C&XLdAABs8oN!<@8Fz${3Uj_28ZwBX#mZBO1eFKu|Iu`nQCW6fQ@Xpm zyIZ=uJEa~%knV1zMH-|_x+El}5v04jyF>CjzH5E=@}Dl1>%PuDd(X_C2~At;7=BnZ zvp83QQTYIi9ziaL!kwr&<<5xO9E=WKrYGQJ$|2~vb=f7bC6wiQ8_M}bBvyeEdr z47lqbaxq9Bz4C2DNGBRPPYdKt|H;(-A6(A|jT;00YQ?Bnx5;|zvOuE@aRazlYgE*Z z=+HPQH7TYj?udfqRl^#B8=nL)1OC0}bpnK5k>&7Jd9DhNLdY0{2G{DJ(XZ&?;#J#w ztt1&upG1hb?*8@m1Do>Ne&*|2w>>$+8cSQcCfRub{_D*!#=H)E%m#2|erOzK7h_av zOqfCXzG)mb+sOYA1iRlLKO^>PnLSR1%_PttvPPGje(*QUXC0J{oLBY$L?9?&eiMZ+ z&ACA(imt}6of=T7iV!GDgoMhH zjnYwc^TqXWrhygIsR~^JB3|M=4|_U;Dlda~Ti1#z``GftKi#O9SKs+BL805$VwNIp z0BFp?5rr%EYeGw~8mP+c^^qd}e*jV|k`Zr}yvG@Ei|t`SW-iy81AR2IAD9<8Q`mUS z-hOSO*KYjSuESF7v$6)|(-_=(>GHt{TsY+j@E1T%x3inQOh{acCRQ?~w%4GkVbhCA zK=~mpx_W#EEnap5(8f`bPLn075V$d+6&QhF1Y1aLB#WQ#wI5pD>_Pwp-=ljFY1OmO zs7QcO@3N!p)kf%F>nPEw>Dif@^~gavym;YM#o<(sx06YDNa_Lhzb&{zLLLMdqSe7N zt{bnxKL~1LM?}T`o$K|0dI0`n^!4)tO=Cg1zl(Yp)uF~@XCExvDq8#+#2k{8W=ug5 zsb@=3|K|>gXp9lI)a2+pg+V6sOEg3e`{{`)O%8hjEd`7a`MQb9oMcRwV4}tD5G?!| zfdZ(W9T^HR@`$B#z!&FHS5YsoOD2?AZEYDT$eg;mily7sMoGzOsmKOc^ z3sdw#MdVBrKhod6{WnwU_wR-S!F34<`PGj_Fdeu)O{oP{o#`l{ZIW{27~f5OXdCvH zvpeh9&hf$MS~K+Wu0*rz5Su-t9hhSBk_ar6)3w~@l0#jy1&?++Bc72{e8ZJeaE*p}W_v(kb%2 zua7CNGDzX_c43Uc)n8~D?RvPJ^m}oqhl0bsKB->}3-dykc4`Z^#V8pZq{se8+X68Y z29SD`G)7#Q+s~px6MTFu0q$6H$ zl~@rd9vp2sJksFkNX0uRYh!|EuIE_ReRi$ybpGk$B~ycO5N3jr$E|EOBzf@BuhW-8 zlJK^`*vYREg^f#d)H*l(A66+-2;8@0`~pSk>$;oAO;1&t8;OKm+IAcQ2_ho_ESm15 ziB7VeS*ZTU_a~?I#K->;iy$BMA7VC^ZSQvSu|oZ&G9$xQCRVP`;_7OU3W&0Fp%P;( zSmm|{ri_4nxeFUFe)~-I=|xq-Hysp7-)=I&jkkc{9DDIH@*TG;*;MA&uL+k>q-aIO zHsBwiq%?wtYx8$mbJ3+)KTH4J9{TAZbt3U+o2bhx+!E7Q8C1!6+_ik-s?tynnhTRq`)WD-8?o}17mkK{C*I0_|DQcKe{rCd9>tf^4wp%}U69&hM`oQ)wO4DXPCQ@=;6q_?a@UY+ zI9Es??gDEa(i+NyALo#eM8z0`Dw6Z&gT?81=6L0jjhGyc;5~2pJjT^>#>mF+qsF(r z-H~I-P~y>&uwxS_@U+>#r|lHzenQ~VtGIhgPH5?d=Q04;J3yr#eCatwHfAi{*F{Kx zW5ei3h7Kd6Ly+N52?(e*1leEK$Otl6E*J4kn{rQbZ#4D=6F_H_Lz^EscAN55~BY!hos(pWWVv4}XB)K506VwRuy^5hQk0<4d9pr%XU zE?@3-vQ!{KyMZ^yUyw;lwD~(cGTzhW?F9x@uPnz-;cjs00JiL(s|#j zQ-GXcAN$C{;uYZVLA?}tYGMis;cptdRyAQ+5(g_r<-$fG{jzh{Q_lkt`~W!ze!_u4@(Lcn>3XOWu>lljXfdb_gS^3^aN>q zS6|d7P_;hZFiYV#usO9Z$y15tHb&p&DlGS2vv6xK8 zPxJatPEivJd#6l5_8y9E(eWsxZGV4OjOQXMqO2B&gBajCkARlYh`mWC+KQn4cj#PM>OsfE@!uA35D5EM zR5Bk@zQIi6ZXncs_15IN`f^4~!A@B53h8{y$%88%6!^jvvHiPorfj=3CkYy#W;<#( zbEEf=y_6`rmK=a3)9;0%Zf)A=nb{~F2$!&&+BPd{B)r~U;6YoJ=W0!)^9hH@Qwv7_ zFS`e)-4fO5TP!j8i%3vIBC*KQ1r$&|2ol|jmz2|9j%$-gL(-|*>eW#Of#E^&3o4r8EGRfP3+oC5loaD90s`BAyFNkh*uZAs zZvX~9j1+6_JzAX`lOW;2g6L-g05d$$efXY-|H_58MYXy2C9lovo0z&Z!};r_39t1@ zp}!qqn&+cFo2B8#4$d%tsjWR?J>~FaaRm$iEoO{aZncb01cj5sz}^x>j1V9ope8FkfOcJ{n)`Y) z;t&XK?uVN}Sprj|@&lmBm~q(*>`}0uhO_X*gTA5zASI3KKN|YixC_w zVgMx-CZ{s485qi6v6+DZeWV0^$g=PO$71;^3Kjl#R1aWW^Z;PGTgCtuZQpgOAah3r znO0R^i5>?Lfalbg5z{czmQ$ZAjvj63JlZG(4V3{e2LYu}y`;%o!JG?dZ+4rT zh8Ty~t75V)CW+2FHKuY~IDZ_yDpGF3glI$<-ps8VzlSae67ncfa2o>6`VYH|4DcGK zeOLB3Ige(C+1BZ49ZOijT7&)m4EdJBcsff>H}g(ciXh`t%<;ahKZ^NJ#qv|{YsjHL z8rOqV-r7wqGy!*5A-xDMf)dlMZx4T?qmx0*$!7W}DF{W`3HdXDl%Ss)uTxARXVTd3 z1{7;??1ebR67sh4O`Q>x+mZ&2jQf+a*Z+2jjQx3{0fc{ZYN*irIRzSercx%AQMNeD zrx6U)4u{YY8fNRx3(n|wq@m%TKvG$|u^MCX9z-bW4C91tmwCv6noYi1XDW7DCN@=+ zMDh>c=veSk8trz_y*R2!*x4-uch2K@!e8ulwy+fm;`^ITwJ=22*5LFYwHEKcgi`2v z9|Q$Ymvvpalq0@R(7=3W3vt}ZhF0zjOq8ok%2G-~M`521*uV9xne( z#$g&6$tD6JQQ|_EVev|+*pMr}NYAYb3a{yn$fU$Z#U*MCT7A%A7)3vwirC{gW%;{5 zf0BK6t0IT51<;veC(3v6P=ygIG;whUKu(mX=3?GFep_y~=Jv6fEO@RQ4-ap_=VQ$* z(+tgc&q16$HawUBquY)K%BQX!FHGl)mDyIGQ%~D%$>Pbh*9^tLwB-=C-8bm)c<*e@Bp zHdr2fP{Uxm2Mvo}`mVoX>gTdvGCW&98NJr~qizetm0wYe0=>t&h_L7S2QdKcuRqT3 z;3h^0RhyV*GRt8%%XYarW_09sC(Vh~n{bDxfR#6NYqT8HU}O;Un38Vd0u@U}(n3+}sG{KBMYXL;!8S)$;>AIP8~wSl$gb z+f?F{9ellkdvcBC5wL}v1d-g~fQ@>u^;H4zpX;%bGJCKC+rcb`v0yS_=dy;KY;h%s z7y0J7^fAA6hOO;y=1Lj%_ zD=^phjU?ubZHR1+x@`RWKLDFS_(?##5W{;v8+mGqo0|GPzsJc@&c0f={M{ZYD3zL& zUqHAP4>|_4=WP{62uvekr4AozM97rJuKpI9co5jOP@@OZK;Y=91LTW&fME6MaGW;< zS8RKMT+RU1tOe-c=3KnCKRp~APTvAFEn`?RNBI$>?SmLLFj4JKq=9fdG=KWN6%Q0m zl`pipbk@L17*QI3u1%o;B8`o&-n}BhVO8O9y5uH0ew=w&vSMa%2!P6OU*$C68N(B) z!fhf8yqZ3Rjkw259$12*@y3S@tn~MSmf`tE6CJeHmt%q%@Q_8{%YoD#yj(nHz(k5Z z1)YeZ!`+s(1vPo0ONX^1WuXYAp@4IcEpd&FK0K7pbXG^NN!~>al|5vUo<(n)ih=_X zvw&iAJg_%(Ck!2sjsO|F*pAoHsY3jBgMi(xbr=Z-{B3+x-MZQnRw& zDBPizfOR@;l*>|qar~9>CkTRuXZ&S$H$#r zOtSBk4leOwZ~qbzzQ{|3fh{qlh2}{>VPSwdOT+(=JCKh4-I@=+k1*miu2{T|nqZTH zDu!)?1`~UtBurWId%GVGg@kI1n~T=2|B&K>!VdtZQz(uc+Ud8w&C{Bz?OawwCq6M7 zN%z~@&Iao@{jy}?(^ZB9D1=&%z8^W~*$)pj)cH6j#a&#A1NYKtEZLn~Ehe0GMJG%I zqHJ%Y?6I{|FD)`Rx#J%8_jEX43pMEk$Ayx50YwjtHZlAjZOYH5ez8i$SfpRz$9m(5 zq{Gq*BcH;wx|(DPq@=cG-t5mqRirmu%F6JN$%QdA|M{GlQ@t08Mj09F=DeRBuE#9G z{Rl(>@}hEOWa7B#H_SJ7uKjULEq4-4R;P4gpYr}g!6F`>u_N`NkIxN6wE(Os60RP| zZyK})Nz^)*m%lf`FfsyKfAD5XR&%P2Me2-ACt!iMAPa8!@-W#ZAtb?HD& zsF?(swF@&6&;T6Ge1~_T5*kc(nhV>-9-eOLSdj(dI@cJlIu_+A3#QNXmiei zu_i-^KgD6yPPb7#Q9V^LlHx0QXx1|YXsJta@S}9fXqR=w)Gf=HOIw2hFbDQurG`^? zpD#jF{$8_`&RW|#W6?@+0w#un!U2H$dw0t*9~Ul83Ie=aLV$p|Z$JRtuV&oFg=hJM zjnq@{Xo(`Y{alX5>IT?ZkMpMqGh2pt-Je%$&CpKx5phtX2Y+YXdFYu6xC;Rr5}~0X9ANiC>+C%H)nf7o#LAMkg2sat>z{d2N>+Br3Xve; z7Flp7Gbvb(;spZw7XR>&@E;B~k%##fT{jj%uYka0G73=)X{8+GbLl0`=89Um^|v@_ zh<d)UU%GLYzKD-if>M)`h0xx*&~DE}iPoj&jl^JI@HzP-|%EaY2* ztNGuGkE*D0$A;qcsdN2RpH9ID1$6|i(UiULxN%?V$jiWkgi-5#wj$7 zcRfnt4RJPp(pz<_Ewc30^n#ApjzD{D$aSx&ryc?y`K}<6zC-r7^fPx<>2O_v+ZQ}b zHNN*b_=@ip#GRMk_3t_Zp$$76k_N(@Ay8H$7E7qywxg?*bcMh`0OkC4S&56k@r3Yb zZ2#9Bs24%;2--A1uK;h3ZYTpIaE2MLLStI&mp!6E(gMdoP>$Fix z>$Osa5qqKor~MjV=n13!fdT)Py>{4}B;8PkW}2&xN7Hj`zoM%13J6lm?dUNu9KcF^ zW+LXUC~rg?rHWOzCKgS}qfaAs#Hh+>jV)^ft2-S|wL=;|KnWoa@+rc(YWVt3$uwN4Oi7N?+mmt8vrLY`!IdujIMS=D86bN8Cr|)w9~JY6 zr%Y7miD7q|VIWXUeHdtHj}u$XMVU@f!M|;_NYrG)T=OM2V%!VN^-xL zz4%ahd$)}(x{9VeCpfYt&UKsV(6dBvik7(RV1NSoPwen=zdv1-iISoq)&A#)WKKt< zGJ!8>SSE_3A{_qmmi;`q%;%9ADbb4dyI*w%uq2uh!GokGATS}1 z5q*|>y5lus4ekz&`FE!QQ@*>i+39v~{^g&?f49-F5D-)V8mL$00465FxJaF2X|TB9 zQ@j@k>csPTAg;$bFM4UCYs40wn$5=8ubrJT{U+w11wA_DOr1QfXble4cVID&h1qDTzg^cY)^D>wZ-Z85Rxf zr-1wv0`8A$@&KHAeM!3Tfq{ft1+zvE*Z9svgH5q2-HrBG84*#}Ump=>+94EgFO$Rn z(vYTH%-)<2PrDEfPt_QAa1atx5MN>SO)OQbBN zUNm+34%*Fjlz@)#f6YrSAh41d@`(kCKw>n~!P@FLN)HY1gL`p9_tO+TV>>G^avOUB>E8#_e(aQCE#pX zcU_sjv2rW__CZUhObU4CWYQ=?0$qgN&_{<#?t(qkxmWt%<+<4|AV4H`$znQ@LtrY9--J1|LQETVHUCF+?=YNNwRWtqY`ypNA2lBP z!h(T((>}lT*cT7aJ!2bP&9j$|b43*;fj7NNLU&`l=yG=M7Bse8SF(=nw%04PedN4f z##rFZdoq+X-}*R`qdIBn8B;+*gk=`Y*NI?c!C{27H{sMMR%vM|3frpvq2m6f#S4c1cvJ)?mw$ZW{%&9) zO)>J3Vr7PZmDb%&g~q4f@<*i;m0C*%LU8iv=YX}Z4Xr2(k}!ih6Oh|3b;lclTl7PP&Kg+Pup ztY(Dpm!`G`{toAp`s$NnejNhuNth*3L*!Z*J^mcrcjSmoe{umxN)n)7G?$UqF1_bf z-?kxNIwGIidVgjPe!@ld#@x53JAS|JcW)U1Yy=5I6lZl`z-Mgo)D#qvrwAa?;P*B`eVn9ISUIiMf%;KGQ&i z=fAM&@1cW^_Iz@TuTcdnu3J7mq!=xI(kQ_TXu!mvxE|pO=jMr$jmtx0_^`Dxr?`2^ zw^?ubZE)GaKIwyDoRvm))Pk~3llGaV(W4lcZLOyW)U^kPxvpyh`|G^xQ`*kT$whvJ zCjAHq3Bv5dyV*wdVkl)Rtj*6NRE7Eh{Ff?7XpA>*@K_P5y@>0NuF1Vs1PHz>*OC@&bTw5R$Ff?%2xdb@5mmsm`BnD<$_)& z-9=G>_@mquo5t=t`(vMbFV@9H-_cKfgW80%@5b0(NP0TIKA#+Le=feEUBg|a6xlT0 zlB+67@chZL!=`9V-Gezcm>e+kWc2JgEtF&Oh5`J>YaAbm^|j?(Y1uoLJ9Jc-MnFwWbtq`g}buE#2@4<=C4+jS?WQV{<%)+ITIerbuS9IRwn6<3#p zncvHa5m)u#w;%j-bvb7UhYk%6)}KGI@3UQ=`0L3~k}#^Xsu9FUeX#;=120B|oyI@%g42e8; zna6yndPp;U74LxikqMdOg6V&~pV@(-Q*Ohiv0B2SuC9`qB)=|Q9J%wU$OT-()1iut zW>VxZ&8E}ff*oRXL0qRCrtC}z4J|B4uR=s6X1~4~<}h+q=HWGb`W^_KOzyrWgV}31 zpgonekrdc{iw5@doc{Vdz1@D}sNrg#rmj3VaO1rpNI<1VNB>HV6C(|LV`YrJX;M#@ zS-5%Rk?}V+bA10W(6di2&`+*Z;y^PXQq#boL!WjDnS~(5Nas76poPLUJFRuT^D}PV z13O#6X1(A3PUrs7ZyHf?Z%i;%i*e`7n4v;Ffq|iAWQq$5XSg}qrC?T~U}YWb3U<)Y zgepBk$b3~>(F>+l==&^9c^EB3lAZKj*ABP5{K&amK(xnBhd^jybfeqhIUxAR7OJ2W zlcY+yK!6z0@t1dysoF*t1QvKx`G)00& z{%dL}O9USE1C&!9_8oTD7pPkM8s5lGXTA}`@6xDWh~T&3dh>E78j->xvLB+bl(Q%* zIDeEE&|h_j5K2#yW_}t7%CupVi(EmlwQLGM1J{ z(`{^L+h6N9IHH^drHKZ-AoHR93Ihg@XB;-^0xeWO|JBh$DT|_!^;aDQv;2hQy%c-lEz_{i)Zzh)YD2mwq9dfwPDbaYSj?(;wE zVH+Dnq)sXu307ybgi7WmiN>}Zc*XtLPY&)dDb$057fA^i1)ZZqwKe#!mxO*lajN-c zUDFWj^9rs;UmN|}T@jM%KfAiGA73<>;Lt%bdT-oT{bmlMLbFcptRJ-REcB?7A;h(X~R_JMA%^ zj-m%ESgbaG&Cd9K&_n)SNNe0c`7VTfgME4Mi%M~zIci%4s8|g-HE5Lsv(%>SrFtU< zA+hS5?BpB~Opi*ty8hocQN6tXyTVnl>QL^ag6w&V(ChvTAd>a zirl_cyp`po)gL466?P}sw41Cjx`V>~K-TZ2`B|L0JRh>?jNAQMDWe(pbC$bCGTif7 zyq+0siA>La8koJj%#)-Un$%T9-xdqj;*Tf|;upk-s&E;o*0gzMdT#_(;P}F%c5^0sa?#cmcPFVSYwC0^MCU3`nwCs$@xry6HvcJV8GVJKblU&E1@2hf!t^~Op>C#Vg7q53U z?w1i?REV}OBZcmbn9n=#`nTipoF}DkPjlcO&zfLPsu@gO_Sj$9uLz}}l^-rAm}(z< z)48#8TJDRan*Oz#bcz~@w6BBXZocjR`P6{V{V3JV=?9>98l#!og)h+;>Uwa{YfTKrb22QdMavN< zC&kZNkJV=C3qGnhbms+4mYQ?h!mZ^?W}>xt;H37pW`C31^tOihW^g`dSOL5x36GAD z;qLS44HDFuz?tvu$D0R5|9$q7`A;VM#2l>|P%b0;7O7MNtifZt`SJ-PQ0s6DEjxF> zLPK6b;87~7J8!D7B7XhtR|xP1j*HW1LyqC>Zf(mNrpkeAj*#r@q7jk^ND zrhVo^$+9W+njE8mcztJAwGuOJM>m?W(49SPgXD8_!D$+l38n(8Xz3$U;tOycn#wm}RUo zJ#QK&S9g^zx2@i;OL0Ue+1mj(!%(ck;l@}Fel#QquLmQC>7V2Qs(~sA1sO~uA#toZ zW&@OtdTtI+q6seEq%~)K<}s7umF$=na%*M}O?)#M#mtj8rTpfF!B8|>AX%f{{@wPl zdd?`PcpL`FVrpn9^3(qoe=RRw&yc!T!)KaJB$K{k8~!rF11;d7TJN2dIQ1B=bjMAYcKwj@pol|VXTPbroQvaU>ibvez|izs_#cJS55L^t)=wAW zr_C%3YPxTtho6V+p~W|<&2-rrTVDQF zwp^kfE}F4{zh}-e5Mc+$rtAykgzyI}w0Ht|&4@Sp#T}{AkL8=Uqq&;f4jXS{t*_S7 zUjzh1Wxbkv(mB4NQ{iKOwX_c?tlDFK4uDXf*^?&q%F7}VWWG5)w#m#sc2j_c@VUF; zbhTm`7s3J?*8GQaqj&;!`IGOgZ|5}xex8Ic$$&0{cErNW?A4R|@mt_zRx;=v#tR9E zWfH#~m3-1QX+sh%Uv+0*`T04I()CS${?mL&KhDJtF^jgxv#Hk!>W7E?!oulI;+*G8 zNy-rq0G^e%oT*(!4Ez6~0}jeFGx()7X>y9!WR*3->MH?k!$^Env-ryKA6RIS(AG*{ zMg=g+5qEcGemziz1VagnLA814H=q9k*VU>hW*|JIk$)pEZXx|rR^wu&IeVBfd?Gff zVt_vaPtIquPJAqgz&04zyC6^8u1~q$c*ACTCI<;%=-;TdQB(>`?ZPvgj}35l8xwQ8 zl!dzjohvX$*H;SrQ-|t<}?NsJzKFeNj23=K4WKO~TKCNm`9g`Z^st zm`}XJ=uj$!DZOPsN%2V%)ZhYHB>^CQozW9dT8~?u;gx0(uqHJ#Lj)mTF^iQsGs@#< zM^NPOZt*HlL-)yiv+UN#ez?0eW@6@Js)+26E?+HSi1gGOqBwO?s5GAvKE_+Uu4&JB z5gJG#u~IT`-h3H0HyR*sm39{w6Vt(gba|Ic+_nDWVdq^N*jIZf=NqbEAg^gc*VaD3 z$#hr4#!w4+2xVEO7k_qn=QyDX{!eTNj`AaF3EJU#lvF3&t@ z``M~YP2hPK`nl98!Dw0s^e+`nrx=&vCQfl}8J%RZ=gKG^gK(l~pM&eK&=`dlUF3x9 z@-nfBVWXxrd>okw1d@Z1N_&~ljdt|Q;gx^zr4V914v;J0(;yUneBazb9W56UNiEm6 zK-rx4qz5LJ=~YDrckN5>HN;m?2f(2%Al*)Ii%=#ZA<6!lM-OZ+QWop6GC;yjrT(mx zlv}N@cM?&m{fv3G^?DJ?HwZ(QbBx0^vvb#qrAZdqH1p{>j54Y3dv`A92ue@^c&} z4-hWC$}lSaLjH}VJ=~D6D~ofkk4*am6>Fh?u^@fPy-)r{gf4^}zHf;#;~P&%-}fA9 zYCX9~VGpy0Q432wg@|(D=Zz9^Jh*Q>t1(++OCt9y*0)gM&i|2)9MY2?fz~5nD2Tt+1VMf{@Rpi=y=-m z?`e`8Qwn#4O8d)%(!!1^1nY_fqy73^^<*k#qTJ41z~-h{Y~sfoi0_SZ&+7B-t=Rzrf%qbZ@4{$nQbM~1QpXUrU3jw$-;rFDaAU!3vp`e>|OJ|l-#R@&&9|p zW1E!?5Wj!1!o%k0>p#7fyV^v>W#0GP`KuYgSk9^$7xFjK{uWmueBP5dSVn0rmblk) zS_o9{(Rcn2#`S;SDb!%J-^b4y+GTg3DRRQ<)qHfZKWpiHcC0SEh63OL2vwslDCPX5 zgJNbz7pSTOZqTtTz%?`IQBy7&9r`ew3cwe*qoW+rEV<@|iyz?)@q=L(7l!xc$VAKBoP8ZkS z%u^XcGRc>NoCEIY!^O$dQu-hpb$@-zMGqy3LEz&+|K@+-t#8+asqUMf+tHf zHRS-nUkg`N85tw9-7aqNA6_75XJJFcH%+gGhMe+#C4+%uwVTw9~~`eETxUWC0Y_*N3hF|4PPMBUt$ zLgXrvuw{vr1Ng#Gc5h-|Z1$zH$5ho&DWfnY;Iyk75K&(Of-Np!n%Fz=V=>au@T7@CUIS zh(0t|yTJ`30zc^TKCFw&#hhZjINWF=rc0O?xe%!zRH>j0o9tEXRI!+lGDE9t-{#3l zs^eHli>q4_`i+7X<+5aQ{<5bv-s|oO4W2JNzbR4xTia%FZ=$tw5ZZ!;W!p(gyw9B7 zj5nQKQAQ~dqkc4upYPk22m={$^u^>%je1tX$YSn*j>Q|*=0 zsi|;7?>?r+!rj}XDy1V=NuW_Bl2af;7LZdSQYMm{qN7Mf@JH24oAKfkWX&WA)F7#0 zpc}5Ox5nMk!$U$YT|+`zg(9>KMbk%G{4Sa#zF@CZBzwIXt@r!!387cx@gV%yzX6A$ zpju@Mq>n$m`VuA4@tN1Tg-~Am(_HK-*l)PF1=glt0L-y!LD4~immoo&WK}Yo*SrTB zkL{P9n3Yvz_GN2d@9ch8st_$RGp%#wh@T~nG|F!FSawJALLW#8om^q&w9%kav4)GO zLoF$Q4S2)$yFs}*M-6P#SKPPxdjW2NPNMxy_GSLgCw$^PO;2<~Y;9Onx9c@ubs+lv z@7YVY?Y%OD!P4&{vx^x)c2AC-qEFI!bW!w?N`u5bqoJ&Ohdk%Cm8MWAYqWdkANu)W z3Y)EWX0v%wO1Kg-4!2Wu5dkbXS(RB+KUzgn^rIz}e;F5@2)El_lC{vYj^iX|uZkbK z5P9}SkFt}?a#euMv}~ystuJ1@nrG8&9aiMbU{Ag#Y(1G!i!G27Ik*(CJ{|8 z=1?6`Kkl$GM7Iqbz26)AlwB09<_0DXI#r=xq^Oz(ats9XKMUL&>0mqT{B5djT z*v*bZ0dbmGQBlE3gt9tX;ktaIy^Qz=x|CQ=_4sG4n3w|lFOF_*=$$55ppOMy6MZx- z;$MD5BxSG_g&dMMRgv~nS?WPl78H>n;-bfoLu6Iyu@hXHSeiLp23)NRy2yWN)U=Uy z8^7w7j(+m>Tk@PIx7jz5hptDk(^1CXf)A~S?dj09DL@BY8T^OmNpUb;{-}(z_!*UH z(ShVa@-FZlEwaepmqv>I>bV`X)loIs5*Bor;FU1Dxl}v4&T1*Vzy_>k#`{eKFM{Nm z>*jF6AC%X7sciCy@s=8U6J+*$j`td`&!J={-oo^|gBI2M@H&+^bbyJF}j9uN9SZZyDTEV;-UO~~}|&No3SiUr4e zLFr8*b5d7b+n#cQ4bB-(C|2cke5ShBJ787z`MT{VyZivvT1h#h@uF%2Pe{bTniQb> zI+?wrU>&jU<66I5x8_QREq@TnY}Sm7+TzpLjWBWkr5igV2=F{ne!6+YoW*qp|h$o1<|nQq_997hYgfKZ9QE)ea}Lj@_S;=Ox|#H zEemR@!fd0iD%|&;4ZQjn&k^4gJ&2UI^iZrENL(0nZv~0;)fd!SLuGY;b$`kfE$N;g z0R#yh3uT@1l0Y_~;XwK#h>-3)F)xorf&CpTJLRyW|Fgrz+@_LoEg zborGL!r>R^Z4_q*xYbbJ(TBm(8r33|+kfzSWJkolqa|0a`l z8KQAl$~rhYaIoop;rC!{!qz##GoRi}js*;CuQ+0l-z9mXa5?VYE%gmif-ovq*yaHbv zqM`v^i@fwBhx-rY=nz%RQdGP$HwCTtG)=d>^^Ct&w7E@1-hIcUH-W&R^Ax&)_Q&Q< zp4_mvGML|75xL<6Q(Q#c2U}RK1RXf}O^(M)-4bOvWfXQx1*lK+OAp&*N%}u5(54We zHHSI>)e==93{~g4jDVMw=WQ|?I>(+;*FR>Bj7IL-D2k~IKygeD@*P;+5Ry;@kxwAT z1M+BOl}WlsjFY_0R%I*MmWOP_M8al9|= zr&BTXomA&UF*U4!=5P7=@`_cLk6pW;dt4S0(1`B4zMU?4sRUpMy&Bq^2nduQv_2Gu zUie63OLv*8vp4jYeAR`Av7BHdG8feCkx`c{PJK3;j|m5DW^}i_uzsy0Pwt694?uN5 z=Qq08St#g%FUohw%ETF6ZvL^b4@o~EK^wqR@-tHy0bl;?8Kjafh_wqxzasF5WiZQy zENtn1pZaF9{&+p`V>R}1{T57J-Y$PWuw0H*z38CDw23w-H@1Dr?DR_ZZc9rvjo*tJ z^5iJ|{r;WNFRQinUy*`)Z&*Qe^X;Ll*aKlB-OVrGnhUh;@>xXuewZjut3g7CEESgQ z@~BpbQF(nNQjIa~#k$!>dAuOKJ4l0yxF?(lgEfM5EW5ZftTO*RhZi1t3^xxw+TWyW zN2{vR5>xOQ@yzgptBvmz=P^$f%CbcSMQ zKhk!Sj^g;202W2wk#u2A#>n6fmB_r8A$G^skB8$0qWH_x_lX>bPy|UL7kKur z5@Aq$BS978GJcy>m8xUGo@renw@$1Af^?v!^azB@FIeXRs2$1J9|%Ut_mrZ2zqlV=sY?^Sr3`kr{9Y7 z`cYwjMjTx%Q411+9N$Cp+uXNhlMB6P-4Cz0Wh>rCyM$|t#L_H^CvsiS3wCZH}&QV34~Xx4VF~VhE{-*HtU9`B!~&h9m)$N=Itp#|sBp>XD2WsX z;96bZUj7*u;sF_TlzQQ}gSC!O4H5waF!$p_L(QJ~*b1T0Sw=evsOi#OE`6HB#v=kz zO;Gm#3Aj@N>BD%c4FfdQWANXF{bz0IOb!K^YBDDgyr$UP!>m`g!>#>pIK_uvG7Y`< zg-P!|vOIp70jaK=gr$OVH60WD2B~%4~2L8iK1UVi%+GR zDA?d+dE)u~f^04BKFJjLke&KvEDA7n0`M$Z~c8dBj9HQTR)Jy)5v`#OwV(n!Y+J>MrV9y1TnUT0pubWB}>z zmXPj7Qo0*N>29RqA*8#NZjcVi0p9ETeeYWSql-0+GrxQ8KKtymx9OuW^ob*o=f&VJ z&#S`tIgmu?Y6FZt=w|L>=8rN`LA z?Y_mapC(XJWgEGYAz!36{uV|1;-7%AdUvm-)s#XO9|s(R{u{_U5D5iZ4cvDC$XjqMK}Zuu8W2QKp!!A_T)!C-z8b6h%O&3TVS-TnBL2Dh5peKR9U-tTG z&U^je69n7^2Z${I0M>L>VmO6fo++BRoVLQ?2V2g74`S#8X zLF6UTgCY-~EUB2AF8Tgs${66p9`lMd6UE=J5SeaKA^Ii2F*F;*l760KO3GeFnMfV{ z_S&ZWnhqDH52*0bCMaX$~{HL7sA+`9sE$w zqX)%7M+N$Q_;vq}=0Fd}V>Rcg_+G^5ZqIkg`xRviWm_@%qSeu;2d-(|EW12ah`?+H zZ$k8*y(m)L7x}Ylvu-Q+8K!1$#@}j=XaTcwLV78ED_L(_))8^682v%^VoO{s^ z#5?Z92eN&HdZimJ7W4`3le4g)AtC^4i*`}?+f2i)@1BHgcbF`;G<2CT5YZOT{&|td zr^l6s0~^Y0H>QHNYbjje!JGteZ-&zML=m*>Hgm*u`AZ3;dE@^PiS1}}rbN5(A58Tx zaZbznviUor(YZr6z1NXL$klPo-OWvimnwj`r_0|86jvI)8#x?_6wPec(!VX#Y@}v6 zDyy$fZ1=;S0O);-1_q*ldI3?llpyGWo!QR@26UY@03=-vl z!VIwnXCV@=?YHDK{zh}0df(Je8SzW@lg_?8{q(e8YGlLv3ozfiY7bL>6L`k*PtxV& zO00dIIRI1&^gWbt5)zndQz`>9!GHZyn^D`DW5$LoFz3?$wMV0miZsk3gqoTF=*eg{ zzLycaYshCA8ZoVD5}~}vp~X|NK>ai7<@iWTc&h&)w>gnnx9|Sxob`=7qJ^f6DnS~# z&Y;4P_y8x;o!2cc$AMV5^I=GBb|3PPB&>Ww5IKD*{KY7@(ODOV<_qX4(B^b&fy z!sW(zbz8mFc@mvKKmthtW1BWvcT>GZoEQk%(Bm=@ci_5bDN6>1>{t>?vPJ)=H>PPZ z;BPVcFd?r^u^9@}-Z!`%{H1a*Pf`T`tf+Qm_8+~?BNqfQhJBI@lgz}URr+*kDlC3I zo?5kRzj=Ffc;u4ecIV6MFH6@cU#RGi6S7_fwv%v>|I3n(UhMf07%|+pQH%zJn_prN z@ZmyM^V{Bt6mh<+-Z2BxB8ea~xNtJz@BmzJC^9m#_4R%`du^?kBfsNL<768^I|)-b zV0UVv^g)h1Aq3#cC>da#n1&47KQICx0_(abJzZlAu_o&#xazR$e%GBXNV?dv*v zyM+Z&1HE%xG-oxFkdT{$?4XPdfnO8u*8pw(JVBD@YrCqTo!4N1C1YfdQ#Jt~?tVBs zk&A)Bm@J(cD(b^O-k+-MCd=P;rW<|zS zGRMk=86kwK4QG&I8iLpwf4Jq*HpA4#s(@9wFX2xDm+V9C8#0>$^}_>)IdYxTY0)s1 z>BPya7hk(~*;q1%XX)%6AKxNJRRx%>mF+jFi8t5f9Ku=)2vU= z#f4o@8=_)@&Cn)*7w0zvQ)oSTGR~u}YFfCD%vq*7D5gaw9qG_U5!?makOF1dmrMx%;xp`m7@xM z-F)QE$N+}p|MQ0)tTZP>EDxq`cq3Ib!n}RcE}(5#fYVAoN}i>* zGQTV-C@8p+0$UGp1gyt^4tPksqifTIZaM_jTChLWH|k~ci^%9U3=Gr+r1r2kYdD{E z5-?eeJOe=*81H|$J<#CzK!SSptgHYfPJmO}ugZofVS;cG-@0XjPkjHl4lo_&cG{?$ z%+Aad1HqYD;!n((;Ho4MZHsJanTp|kuhUycJl+ywMEW$2)Ez;?K%-YN|FA*!;Z;(u zd`Ud%;7yxXHo)qDgLmGUG7w*q`X@r$bjBK#Fs(04= zX2*=IK&WM@U`Z)z&YkdY-rLM33CkXjl$RU`HIP7|^b`ALjY3>h&4RCK31-Uh8>5{S zOB!8d1r`D=hM?{HT9;|CVE0dha&CB`wYL7uYa1P%N&f}uCq~s#(rZ&|95cCh6?c;Q z&BSA4LnMPSInH+$;_Ju8qt)eb)IsAWlH3rvd@rX!*=Y$`3vTV3T%~fJ&u3B1wb%b4 zuE3o2JT*tLHU12m{j|OH6|XLnE#^2$L06qXQs#e0#&C!|L8`#}&l<-Qu+3nuAMqO5 zKzsvsVwf`47}F#vCX|F-T8A8|Ah(9hNv!)ca7|U6`!`;@;pS;OYiSkl8^^E7pq-La zzNL#QnXs@ckxepj;yjqeNOKGlL^FA2Y1#cJp@Q0$Ykji%ql5FYaJ~neMZbDU<}~p9@ab=n#@qR%?2HdtJayX- zC3xH%T`h6%sbYaH5$SeKALn(9#6T^W6JPXWyI;IB+KR)f$G0thH_C#z z)ZVE?I*a+gwJtnkhUj_h5iN2pk1Q=NLWSh35P4Msv0t5`vW|GoSY7zhJu4Hrm=wQ$ z8BzMxru6r}!ofLV8^VFla2M-nMqblLZr}(S+evt9iH(6SKSr}a+OrVVNn^9EQP?;) z1QZ^xTF!fY$m1ro8=H&FINR+oH!gYqQI~lqx=Qg&ij=utgQ~MS%UOL*_h^IyExTzN zVDTeq*|Dbg@Yn=LAL-3&t_WpMPRsY2Vmxzo6k}sVqR90?sZsX4O(lLt8qgN~a3;U}_aOo`=OoBK->fvI3ZG=6Mc!~4 zvaq~Qu&k(osn`c~>>^~~1kHL;6f4u*Nm-syH|2CpR8XoaTQy-Qzp`7H*6N(zay0x)t1{hC zl1?L)^{Z)gB#MAWrh`V zmOh6i`nUJA7HqDDW%)kAHN0EUNdE$VY(=(Qe)GNDwxosgSPops^A+}fSFs@=oCc(% z$I`oh?Op$dyVFMz4JI`aJBtL{n0LrSFyP@BrIIz8r76R^xPYOh3jwoBwu=kN>egb! z;ohi3onE#o1Hf4?=#nVXW5ad%{_K*C#IW*(|&Ka|DGw>KV5&B7w* zr+D{q=T8+@4Gf;;SUPI#&swnT_KB7kj=W4Hyf}&wDv9*(l}dfHe@U^-kHDsR^Tf1 zz5INf9}~cbw0>!E{xzM|Q~xEc)^v*b`sBkUk_u%bBW3jD1FUgIUmfz3et3N)`78Nmq8Og!HhI97${q8FTtWO(P9lOV+ zBOgCp@J*Zq5c0ST^r*kUzbB44SUj|K3H&n2RBNM7%#kkL9pIqINT8}wx173-${!zx zd3j{KX!6GT9WEFI8}i z=6eusAeBEPTTfjHJ?#&bp;XL5X5j{h!FBdqG%|~ef=?J@8#V%rDmIoc^xplj7I=mz zrp!m`&Lp8Zkh*cjcJ0yK*rcF?aS{-M&Sy%L^T5c=BknHu=5noA6gWaJ1kru~Jx4AR zPnmfled=1LsD;Jdo6JVE`wkJFcyY@3S!O&kG5}IRV&n${FH=!bUmxXr$Py;q?=loo z#J@qFME?bfhanjU7acWy**HC`E>Tn^FyIFR& zEhj(T0!d7$5fp~FepdHs`Qoh@6eW4>iPVpK<<_oBAfMueOM?J-X~o@N<$~;O=8t(4 z59?1ReF&C%mDeNVdVeN9tCczgskWYBl~5n-Mcep>gLSYsQj{= z2{hn&0i-<{TpT{v*6*9SAi=)XGc)2{IxyObVPjKYQrZNzQ24{@s$4k1h%HfTu#R6S z_TnD?@^VaC7Ey3NC!8*4L@3LrCOWXjI~`1`3+6P(Q~iq*Nir30Gv0z#r{q1we(E1D zL%rvlv2RG5A1W**}OR_yT>P zi?UeGT@;_4aMf0d_}&@s+W>H!88`7E!E!4FzWX}`>CiF90Ck{Q{f4 zqBL@T4-W#%;~sqA02)$~4eu^!FD!7C2j8s))Qf0)pcNS&o*p7I!{p%>Kr>syf4QJP z&SpeD0g5C?%eUA;IPPR>QIxJ_RPQi790qD+SgU~5p3viq9aLcy92UI9ngJ% z6>)1Ik{uiG{@}C1U*5wY|IuV zq@r&lhF5RfOS?729_bD9)?piD3bpY!_HO@9Hd& zDEBTdxPA{`*QkIX(u40JqMeW+Rl1$yd1@Mk7Zz4@n|t_+qR;^`3o0z*@Ex6Mm}JUO zj3NykElDcjE&cBRt0ka462vSy_<`+z&`6O#gmXH`%p73kT@(aZ=z5o;+>_-hHbc^h zXwCuWmnX{=7X?kEn;ZN=YMWuhTkuPvqUW%F9q?)Pq1`LUi@7D8C7taI^8ar1W&N%# zAlCc$@dN2QJy@F@K%$aPNWcbIIVj0RqgU$wl&r{G37e6Cw?Z zF3w+)-mdJR@$mUwEaUe#6?hxR?q@sp-fx6JZ|p^wC^#rJ=*NLdK#e?0 zVJEKKPquh3yf9ZCp+a-BIJ-Q9t01nw-=qZcRC?QXch$^!{;)Th2p`$ZkuwgCFd&Cz zhnHybE{(~!8aa9HffcyF7SNqv{X?e%z?R8;)#^f zVK2+hMW^xLmH&f4wy#%-#pXM-3hlw9+>^~X;Sqhkl^AMicE}di;-MmP?v90c^SaT* z2mYqLikeDv@&kHy_E1+ESvWUGB;x?2(FIn`d@}2KQpBb|6FG*X84Y%V$v$x?s{sg` z=sRxZ8RF|BTR)u@b99D>65Vmc^DYsd{5t%(hB*kf`Ltdm7@l^aa!_IV*jpgcAqP8w z8DX5qvw)zqz?!wBZ1IR@MWw>hR?2-&lKlC-zx)pV}{1f%SN%5C%m#47!FGu5HXRkZxtV9Xv4!W^LIQe(`9!c}?% zqsPB4fF#^%B1g*Yh_KE5ZQ1v$!MOU6xi&hTb2<*h-&VoPXh@em+xE_97joI$MFc;8 z3W4PJ9Mir(QnNb}$jn^xON!+c^Ey zUq(<%2g7GHBAU6$D(b<7hhvg;Kiq}GCpyswAb-RxP~9u9D8D}obp6%rh(yMJy0xG` zdf~$$inpgJvh z#&3LBPC+b1BfX_1>E3ulQeMseUN)=sJPY*m-&j679CD7}@0}aL4RQX$*y!ia3kWH~ z6`4XiK5XF!4(4n*l-cb6na2}2ulpB$$U+yV=$sKw%p>U|<8LasoRI_@vN0Lxf&Nk` zc}ansspb_N4%b37^cnVt-NmF?q>U@Hc{nBQKTF` z55I)+@AZbSZaDST2Au!ytG!acJ2rNjHj#^SbenN>_7{9_8(l|Yc9=Nx{czinMmD~h zj&*c&rInA6BgW}HdMfH^9`au$oq8ofCM-CVNRNw5@WlN{ImQ?j(}UGT%u{{`q(nuUYw}jFb0rYz8U(bumEdR6PLSn zAjbrEe!iQlx?qq~H{7Jpne8=IHwCap7VkTpDxJGlJds!|^k z!8SugFj>OQkNz#hrYxL)U9qrGy080LQ^LStr$Pe_sJfYEtt|iv`Nmd*!r0%^^2*Bm zpoH4TQzJ^4?S8YcePZHRvRv@DtMX|3z8p>{2&np0%9vcIb(syM?n!L znqWe2_U?|D^p!@_Nre2~2mCY?->%GPI>Cs~QYAq)UJm06Y6 zs16%UjuHU@fu5fj;Kw$Y8I6=1cW=~x8*mrVkxKMJ8`oUH|Rt~k6T_5`*qFW?0BeiEU19eh_yN=~I- z=!xq?)H)EC0p3q+a5l#1OX6DI}qkzca`_7^a7vW{j za8OJi+VcwSrpjzLal9})`M$eL`|XuPm>hU3Gha@XYZhkstLW}eeLR$@MiXHCH*z^Q zTCp}`z298WwwPcy+81f8s#c^xewiE3f71+6D)F=L9doCqzPR5fOyh|CcNFHz7zWSK z5mON`YLr{=p(Eob2zkno^Yi;2qE|IUEOy`XWg+=`O(cA0nqNQ8vGRvd3Ry5G4;wDO zZg#LwrN&-8)WjR9VrH!Q5!z*w%XNre(o|)gmi1@*W|?)VX>=%sSr?tSHln{DnM0__ z20{BP7At>G6o%7DnCYR?EQc6guKeiUmOst9hr)(SnNIgwf3Bw$x4j+;9;3#4<#e_U zCwH2>6FsHQ!5+H;s(f`bC08tnZt6KwiazzL&(tVtLBrdB-YldzPY2nu%{Qt1Iwx+{ z_FkFZHpqpuJtFJ+oob%01t)}I-SllXn4J*UUS1+vwT9f67lXe_R&apCZRA#S{3W<( zkbx_ITw-lSAU<~&=^$+d(H)0*E^5;Xn9qHRC!%WG0KUgzy1QmlA>DA;EQ z-wkKw6LRzVC_!#`^7Ir61bfalL#&fHLh2_l=J@9DIdJ0fmh9Y1BL+OY4C!-xw@%=Z z3dOUq@@c*KEw5Nije-IbEcxzHceaV0UeC0TV>jn9)S=yGPx_(Q-AZ9tOl-9&Wx0PP zn;J@6qW&`&f$-1K{EE9aNvH4oF1#H6jqP2kkF(9#&s}p7b4?g4-UN-KF?TxPmnhBG zn*JTj^-aK}P{MRmexv)URE+Ds4;Sqx!AO=I8i3L!y`i?(57cF4ALO2q@0eXRa4OD} za=JD<>`y$FeBpf>)wkUAUd75no}F4XG&HQweTvjMYUv@sHuc`CQ=X`L*d{+NR3&Nr{b|HTmvFxn3Y+D~=VL9%w4CB-y&AmVAC4zgj@G~LnPl3NL@Lg&L zVF)gJV|4%oe|DXy;~)JU%f=c@=qGl_)Z8Y-t5>Bs`IQ5dpif+v#|_LH+ICV~8$XHE?{@I0K&vqT1V4$1o6%m6 zt2_fkpWnO)W?WFR=^%KDU^E-TEXHc#iqT0V(fbs+ncRP;(oOEx1hqJr`mL%%bsUkA z+)rDKH_m1Z_P@QdeC1FBU+wwB`MPceg3;)!~i{tosM18NPN@d67z0mI{YdtoKrB-%I62q4!z<;u6$o{~U;A9Eh!ut*}3x zW?l)vipHwmU0#WeIpYrgOtPx-BI`M?ZsqyTT~uII-fXYVfm{+9KAy>&{KH*s`?n6g zLjjF5l{i&*C84=r-sJynnU_KUB#=Y?G8%N>&n(_ch}@ zt?-t%NFD0rsr4Tft#dIKbQm^_Yr=@}EEuJHT>2|Eb^q4oNf)PA)p5RR^cPXZP13-a0;pxDO8PibD}5` z9*wgyT4%aP;>{P%1G?9vmBZ`uYd2NUk2D#LvMu-A#M9!m+t~1u$f=cVRJyv|1_{(_ zO9{};YN<3!`e>3$tJl?^5_82X7hc^0?=Q?X-cz3(G5$IsygH#|Zhm3AL~ar;(-bxM z5(IE;?#P4!tRyOIoe*m}k_L4@3M#R}NH9PO`}?;q zeM>K-TkwozlaioyPO)nE%sdSBkMU;U#skPmQbjJo+=Ip=lF$vOms`m&r32zE~l&@YH943hXFCNO({W7nLDG8~}@a zrCg14qP;K3e4Q))-zTwHz`AP%TF{$Xb`f=A%2LjZiCv#kx;-=$8h-EQtKMMUQnnid@Hir}-3daykWp^Dl5S7n=(_;?}>-p+9T`~EoRAa2Tm`)krz>;-Ipeh(sK3SWQMZu%i)_| zix{zOH1|?!!Aa&Hu+614^DS3Ac=0|=*|p-?Wa^`QmQ8xR|uM&5IoCpr=eROsv zdF5;IyHO=dRH=3mEn{P^{z#qqMc0FyHi6CL@+eAP$?Xo;2?TIylVS z1`-^^NxemIv-vW;_H(5{CKssCy9@dXt-EPar4VRBqM%CZtd38Znn&QUI z>%p>u!McLg(6}`N%AzK}Dhe00ROyBhyAv!JdLa3E#f;{~~k4W8|4I znFo-6=s<@dP)AMFA|oEXhO~wV0h{Hu=t4E-cwQ2k;?1S9X>w%_6!;YX-?<}86daa0 zm_!0(&z(mJN!Xg|H6ril6R49ug*+RY>WC9B5&ZrbvH$ZPA&Gukw3Yp7MyLUL?sI9Y zAQw|N4Hbp-4j!d?J>TPl&xN(7a==z}oL0T$kA#@tb8eE{+owHQ&nM&&$-QF(`LfQa zc0_384T`QQW$BdK{S)rGAD)8b=QJQjU|?WqgHr)ed4AqjO%3XH>gNI+2(aO4gvbpW zTm&?LEmxs36_czv@?ssLM+j$E2*Xi85){VC!wPFFmT-aKxUjZ5M==^%2rm@RyHkF~ zalK3F;X2Y_Fy1FVBU zCT4+#sv%Yo{*;zyZ{p%I^WbDEZ1_HdiY2 zmNc`;&V1@91c<@d27mzHLS z!cpN(jlbf~O|j^f$q~x{oPhd~x1KGTR_GtJ$eB(`egZmQLGU|4F&mgEa`w9jOKq5_ zZ?K+*c?AoDlJK)bM}29_Waj6H%phxCFVt~U1!l#S*TDNL?l)rDPBr0tuv@6oh^G8s zw2{9R5)o+SL)C6i9gKXK^Fl-aV{V?u5Nt*w^v4oE4Xxk|GNO1@dMo4|cmzv$tp5|R zLam+a1pOptS>Cnp=u=Z|GDU^II;EuSPWYLxzxYG~zvqJDX zg|tRd&${_RV!`1*6bQXK0-zLCHm)-It2E@lQ|HUPapU^-tvAV!z%x@e zeZ6K#UjviOqc09_Fj?>q#fbALkxH8nxx({#@MsnJBoxLvw;2D1i-c5&q%3~@8Y7qY zT8Lq~54V6kdrWrs1#$JFrZ`+$AQ$H45?{Lv6cUZhEvm;}9BR2xUUQ|)jw|D7J_d&>B$Qc*)8A9NSqBL4U@ z;rX7g4tgGcEoUFE<-W%e2)#2$2f>&MN^udR92GWSCGVi;_s#O}rt)MZfIhYx^=Rbo zyNR$~Q`YiB9L73v7~$l8vQF)Py&c|K(11utG7A@RzH86?zB;a^*d6s}pe{1$|Kg*H z{T>vSk?}mo-FfX~z)i=X;FU`?Z%VGFxZdrGvrKC+864ARZ<8cUrwX>G{d-F*Q%6Zt zC)(J00_h4{kxVlOi<85k)lEFQqe0U3Ie1TL@PLcpZh4^MJm{0j+Klx5<9n|=M9Xn4 zZ20eC7hd$ItxU-~7F3R%?(pL%>XwLAUx{-+2a$hUFc<#{t@Gx*%WwbvG>H&WYpqJo zsy)E%V8Ht^@8s@@iT8CS>tN}0vPnJ5x=tIWJWHz5hTx$osq;bEJU3t`GsQYH8sAc} zq$+AH9CpWnHVh1>Qw|pcAXBlQc7j8|?bJWDgwNC&A|D z)86x(Eir#}xbt?({dK`=I0YtwLvzwA*xJDE&++1MA8#G#0w48ph>Y%*m+d(|p8k2C zq5!#=uF2b8%Dzs4hpoNB?$`gODL+RMb8N(-MhSiehy@TFC4oMRwI>Sy@J*d%bRs5&NQPn$;|C7e{%608mss45 zfcaAMJevC^hK?p@F$&!JR^JWH#vjFWxzkPcVR(msxjTIX>vW)>);@s?0q=(I2cJ1P z1)jcZOWPMS-=ZX_Gi@%R+E(haBMR{7u?^htl4uhD2G2$pf`0eZVheY79I&+oD^K0T z2A6c{m`rJ=h&_w#L}BU5Dz2?#Jdl>u=>{2#TnY8!Nu~#5I#hB@0vj6~Bexm5RM(3& z3ez>z3<05?VJa5L&!8BNPi((`w)Ikc1Z*(<@PV5ofXeE{DbB0znmapQ`79R&BbuXg zMVvf=lc;Ts&AZBmvL;;6k)uXt;oRZMrkVt57-*}1NUz4j+s~HdJ2ty^g&XX9vEnsbm&da zDieVffClFXp;WhycDdl)okvSuK};mlwq%V(R*C^&-gm!FTlEsU5D6*ezmaP5gmtr9 zE?s{qo2h651a`!v2mAgLJ6cQC8G%mViMuddO1j;bcr4JfT3)%oTknIj3o@;GOtgVuY*UA&DU~DxwOSfySMB8h8N}^Rp&LoufclRuGYn<1OnFFT z+QqhJsfO7p0Jk*1Gsj^rFRy{V*~Y+4m4Z;=3u=p-eMP_14q?wGZIQV(;93=gzm6W~ zD(Ex@Vl3X0hv3IjeG0}ltw*ov{@Sm=S@hmf^kty+BJjm`jP-ufdICPG}>}S+(29jTWLN zM5UOkCr?cclw42Bu-nQJzx+C0FaDXgDpnddf!^7IxJqcsjp@vv;rc?gKc)F2nq1wm8N3R6GE;hThL>NpAlNM$=TBGHD=+eYoIP?n zx{y0wv7zVJ9$c#9mBTG8egHjz52G>%aLeI`KmtDTiCejz>kwfEZT1~0+pTxY7OBN0 z3mLu=2=F_e8y*M#WS0j8B*1(EY(%vJFW0U@fkf!E;y`?j)%Ahi)|OI%*>~|$@-Mhs zDLe76)pyJLh^~`O8o$VI0&+MIn=}?+t$3{}za00p5R<+^1NWvZ%h9d7+itu};l%;b z+Z2$>W~oZBfj3W&qF2%vvdBDN=I9Um^+}?v`eB2fq4YI6z;$%4h?jrDm0KMz&^m-3 zXnYDAu|~T9Ow<$VrXpmkJqK^m?fAfKp>pMmCZipGI$7HDt0Rxz&c)YxOe_TTY**u( zf9G0`TFP!2(8msLA`a-O$(bNi<*D&q{<$ElD*u}V+071C^qS)B&X2M6D|T<*pVuPu zS7=SBb3#)u4^kE+&s^-e{*UP3!IN=2@$*Se9v|LyZD0&!jVO=KSlTw5F;52E432pn ze60>Fe2Dyi4YG82R8-%q>TlP)!SZ%~?MX$ep_3%VdO$l-MN=lOc!!uy7v;hU;7q?sX%*!C zx$(Ud3nT+KFx0hQ)SBM;lo=}2q-S-YA`J3)2G(D`4m{m9n+?RkPKYj2y03G zJ<@k=n_pTUL1w-`ss20|VF!$Z^E${{L%)616M~gy_BOoxv4U;1qi&PutI?B~X0@Kf zsVj-6<=6Q8d4B2|Osf?*smD-%a`3=z=1&KW6aIIWURw2JbBQFO78Be1pk}-3AvYB= zoTHF|-pa>q2R{tfd_B_XSx4I@)h`#bBm zmvwO%&d!^<;&scKpVl2LCMn^(y@j5iZ?_oFMhm$T%s+s|_!N0!R;aR%pMR=i$ah9Gv6%l|mP> z>Sk_>5=26C*=fP%`CAp$t10+(I@2Sx2in z#&S4Gpt`-9`;U<)*WV?@u{~;L=I7aV6BKxpL7JjVJu8<3L?T-7f%(C7XH){h=MFB3 z{tapT$E|@uq`T$ys0_X;;&g?db7h$;Ugms8XJvUL2(T);WyOWkA%l39A9Xg(_pVRjbF1J zY{#1xf0*to(b?E^C1|RnWcIpvnRB=~U=U$xvBbeiTI?O`Dajge0}prU3PN7m=Pxs} z{$ORv;?@DUa*!U^w>FQ7-^=Jo?t{mkH~K-xVV6pP;=PRZf+4@eAt+F@R- z-9Onc%W)#nnEUUE^FM~ba5@>&SxPV09QiX%=k35mP%%qmxDb;1Y1zu``ru|P z*Us+L^r;^V$~$iKxO0VC!Mbeylx7^!zwUj+B*FW<2iHv~Q`-nq+$9#enA!Kpil%G# zy&N)nrbpni{EpJM@=GG!krImqEku4MLW?zTruA1Gg{(tc z881kBo`|DhbZeuglbxe@6y_xj(P8^sDi0MHvAS|S>$IGkE4_cPL%YA9UW9Ipc{BZZ z^Yf=3CizsJQLU{FLyCq(Fu_bdXAeLJ5#k3-qJ00KP?Y{08v1IsB>m0D2^ybkC*T+b zyJ(ax<$O_tl=J5werzcJJF&10%mWYTIC4m?HM!N3?I>&}G3HcHtLLGwi>; z*Cz`;YvThraL?i`;^FclB%9BOkUgrPn6bk$MKdXC0#bFD`up>41iy-!F;3bOKA|lL znTr7bNdS7LtMo^0H3Ra$u{8)eqUp=uaMM>1bZ-rn%*QOIEvBnW%B(%|09Cwkw%4jf0Lce))$V!c-p}eJztTE3YnHp zvjo%e%=!ae#7N+jJ1KOoIeX_5F4tzp9@L; zey(2rIycifpo{~l6;rKw#P|C>krku6;_pX;cR2D9g|etal6(Ybrgp;t18&6SY?Wy5 z=)i-P$yJa5=;xu~3pGOuQG4;r%f=Nqb-u{RfYZ+A6if=~Y5afRjKzio(|(S+vSm@) zuZC^VUAvOCAylp-oF-QT5A>pfG#)lqivbl=G3$Z z{Sn^kuc`h)znGFDaXVTF1F*29EAfMG${(j+HY1C#)ekHCh|ZH4|CeV&#-K+D$Ex|b zP}v6xn<)59bvlJ^3I_qT@G<`Lq*z0}hy7UH*{Ykm9U|6g|9;*w@So&yu@L8JIt}bBewq%EbT;p}06!_H8%=485$~PG+LI zm;adYP<`R$Wm~+r=csn2NIgkO%`T!UVCZtH+4U8H0zDPLLC|t?2R=&z0#TYm)LAa- z1ZgAId#a&xMsnnv;>~dVST@C}Nhg(eoRVwx4;h;w}Yx`2!$0tz9oxTY}7622c= z*UD$Tp!+?p7EqMHv`3+BH~eWHUzD6)vOl9>2R_bocll`e^vQAXT8WkrOX=*-{fA`6 zrca791rgEA>LXLu79hYWOe%u*EmiSsZ|XjCG%UCp^?c>{IU&HT{kCt@y{^f^Sgv_B zCs=Z+eeu6W8xk0PuoCK8pxYQEH;15 zvMfCV81=7V@y|%Se`(eYV>qJ-{S zQf=&BE5R&1O+zM&r3za>TDGD(UQU;-3c=mqzh+Y63@!^D;K>eI@%JRj3-C$EcC3a^ z3I6k0;)*h4v68DmtFOg*UNJ*uwbC31+@V=YNgL0P3e&bBpg-xQDmOU%QAI6G!D456 zyP14?nvoDYcvheSro@3x0Pg&1;R=6#q7Zqoc3#?F5Dnn8L;G=&zFXr`Se&u^XgD0| zQ1Go1_4$f{oFzzjkk$2&eM8R}a4EO+4EKSZR}sUq)WqKwX5XymCcUyso+0>-fbi>h zy$0VTKK|Ccf%n-$Da|tKh~NR{s<6r{C7AC=?Y+43H^jp!|xs=9wr3bl!< zHZ%lpg6ro`QZR()V}4^)Gd;t?L6SP(SW1oQXl!(e#WnYzijd|HO>8^=I}5<_9EbOW`~Qq?BFTz}~@S(&AQ$RlhqF|r!| zXT|w>IWK(BAxt$yg6#LKNT=-J&y$Fa^ENNDUE!7HJ8#?=Eu;23n(6~TBe`23cfziM zg|P%FgLYT|vkb(P$s~RA^(3MYZY!u~VD?~A45aWAYuWNU@bA$7uWN*^quCvXnF}T6 zP@s_niCH=X5RbFPspNL+WDb1hY;fFdT%Nc59i7f%xydfpRCxsTCxK5*VfR;6|Cqvu zYcurl*U-mL!SmkwI@&EETqhB4=qt2cu}Xe{;l{uEQ~ZGuG+v2|MhaW4`>3?8Ujsdq z4;D%GYJ$93HwF~mwcTI2Jn+~((*8)}>-w$n_Ue%VC@Z+lWm&|b*nPX{i*M}pAQ}XU zuJyVp^^{KT1(CjF`_*V?LAYb*w1#Hq0;(S7|(Bk z>UvNLtI6!o9PVjbg@}uAT=Rd)KqJ)xWO?gr8n}`U-MF~#vV(kdOI*D@PLTXOE%4U& z94x$!0<7oR1DOkJRYs!-`mm*{$B_z%$+q3Ia_FZjoKaqDTp;R(S%v2{57;u z`PEH+Op*Z{PewIhhULlsjZKWxz?z0>aCD>R`-iblQLNRaG}sBme3f0^&m2Hs6*|lJ zDI+(6iobRm zdIZcI27>_?kg*sz%YY{IJA2#BtpBiq3xxgtUI_4wQ+I-5D3M+TVL<5iPs`|Qn9*3G zD$!l`+ma;=m;cmeuJ0)z5(rS?L$LAiEOzCKYLhNqn+^UIJ#a_>s~sH8QT{kTn5p=W zT?UL_mPSnJdn_WJk9!4bASU#hLFsMyFY=uc)`E&}zasUXqu!$tAj=KayHJZ*>feS8 zzY-+*e@D~y0s*ctTL$P(fu6Sh_!B4pTB*iiMY-D5f|7*|y*zfKqK9uldYWwiUcBVF#^n+jvzhG5^B4!(Z{F`G>$bd!1LKC)zYFr{;pc`M zZ=*TvO&-P*EJD)7!jX(Zk!nIvh+glb&{#|zv{Y`lF2y*r2{*J=WAhA99O$@+6s$>W`5G0^z*#+6v#9lhUHl+VID^kowfFe7*^ywec_%7G3euCZ zyD2z~Zd4kTtgO;v2LU+oKQw)1KvrGXw9+Bn-QC??BHf^*G?LQYA)QjvA>ANIcQ;74 zbeA-IoBR1*e)#hOud~nEYt77>DN;YX-IDtISJL-kJ?jz{@~C*gR7r{%Ys^Y`@mXYq zAH$gc9o3|X&B+E=DQJYjV$k6IHT9~mNE}#r-fp=RUlUrVq=sC!hiAOk-+#mAf~&1` z^4YB<#N?Wsc9^he=;xTR-TCYp3gN`%j9M{(``=GNKx`a6Vr_+&yUJqLaDL~*Q->a};-S2uvoy4U% zJe4B>ENXc0ySm8O?mCz?ZhtL^7^@}eh#(Pj&QR?k<#r;9iZ|W_Q=_T;!wy$rrCUaI zMu?+jXpWP-b(Hihd#N}eTpjYh0j?AmbaG=ELZg@5%Rb7*AxnI)eHkd#Q7BKlNcy7G+Ho{08zP;N6WY z&=8WCm=IW*@Y$!}vj3!e{hIFW1yhILTg6PzitIrUc4{T3EQ{Vi&vRejob8;ZDyc-0 z6TLr*T%94oeUdqlN(~s;Js$==QO5R9u)u}_?)-9^(UL~5& z`@GrwoQRT1i;)=kckcV zn(@zfPa~G4Tpec{*H@>f>ovnx+Km%kBdLRo+J+kqOY~ij37iQ>oNk8XCIuaJS{tW! z5>iad+}!zZE#ClZ2|50ErpnSh*vBuKNWIMqIxb-+bjRYqNkB!msP%2n1cwepKSn!_ zS+?!&vev>QHU4ZrE#+(o_dj!4_cebV1oZ-C*|CKyHTZjJA>2`cZzS&zBgJcSdrx)E>aR>Z{r_N^wX9#`yk+eD;P z?+9U^7>w4D@vzq%XJeW@@TFu}@>r z?d^BHV-)}?Dg&5<&r4eg;F>)>s6Xs7RwU?pzGlCnw@M_}M`C9xw$Q*YS-GC^Ae?`f zqc@BeWN~vnhy9%?VjBc8fkah|e@_doikZ51$YA>aDp4ud>?W*Nwsuyoak8byG2BDHHYV|hrHgK7KFs3BW3Wr<0m{Rr)ef3kZ1p`Q3x}h2!jj zDnM)-Wn(vKn4r7_8*tDifvI$4gnAZ)6?C7$ML}Ke?~kXK?#T=KUGYS@4+yWemu1@3 zF~Nu^XPXhwps7_-jekkpvI3YdAa-6U_ZSi3o(L9f!ox-?86|Sty`E3&A;3Sroi4TT z#lxUD|07x^wv#LyH?ytC>o~XT*$!42K$**xQiw_eDm%kY2nH>Eol(H;O8G9ElfK~) zQ9&1_)`!}?7IB&DEP=?pdxrdQl=SF*`!cymPM-?jPn1ErR@K=vtF>F@dQT82nL^(-?-7Jonj(QTLt)j7wW!DRm+kR(7viC!_i6zi*39?w zjfUVdrui|y$cjhz39c6Qd$LtRj$@Ry>n+-Pd}{fkoo*CIJk}1pCZhCr_NTM!U%P$V zVa)fisb=ECfhLsBRlT;WL3{lpBpb_TGo zTM>Pc>LsNVKi(NlbnREgx!njw9Sxq}%=Y|5Rk0=7sdU0_;Z#>csdnnDdV)%nA0+Y}KsGna34>k1n*Wa2 zBu%pHY=89ULauRemh#*n|4zenZ28*n+aAKAB|g_+-_INNZG^7?9KL*Ytx}!pu90XW z8WOt%c}<8;()yE-zbH}o?D3+d!L3bkM0<4i&kwkN%D!2u%LHUCef&*QtMvKSNat<= z)+ID(0_&$GGPN3N0v+z8^ARZ6D1xz_TyuYw)n^*-#M57|L3H=}f*DVVUwvElMcTF0 zAz+IF%9lx``?Dqj^}Uxp>x=8JeK6m7p?kEBAn~Z5P02w!of3E2E*ibwQ;Q#wz+5*l z@_1|lLv=?Xst|=AvwO3qE%I#f86cRSe&Ms>etiCsDov4)RcU;pOR&8?sUgqt;rq(7 zHpJWg`OfV`0pFuBjW)AFKQ?w835DtkLs-~SMBEi0R&135@mJb}$f{mmJRl2bxE2;Z zNEIkU!}j(-;c<^B?vB|~!v8y-b{rQ}pb@*GArd3ezue9wU$M=ds8?dgY(rb+z|9vOIE8vD|S9FdWh(;No*i6!s zD6zmen76Fc-8QslU>~N5L9X|=A6SlCL znfS%wbq!HB=*Q9?m`Fs`GZMk&*$F3I5k7a*pX? z5HdB@=FOq&t2Nt2Q7J)MB+{C>VQ7bAz|%vpszcM^-VQBnOE9OaQzdP!>~j+i`E)gswjt zlxzO>P1NXm&Z52pPk`VHj7wz#yUg|esT}G@xL=<@BnUSq&KEq6!VpAeIJ zKKxsfO&JvnLAJRgQhl?z^<-l1Y0s-pC|E>;8kXry?oek16Hf^ue}zC2*tZS!OKulp zsCoo`lVB(79K#!au+2tL5KUik7IE@yPRZ^zZ&pwQgd0nz!fFh*~bfS)7jKz$ZZ3)>$Pl^YHou<44SX zfcFBs#MGgo?>smF0wr0|Zx5%@Y<(pm4m~0Zlc=C&<9pT)>;{IX*?hc^l?3DPQ)RW1 z5DN8COlN^GZ~dJ@FijHWBuzO-n_pJ)ScuxZYj4G zIYe+pwX0*b*;DwC-LF#fZhMy19j1i~a;c3kUz=PLjXTf<5q{x!sf=Ksypy;Mv~Sh`Aqe42pFZRA&x{$oe2nCeoR0Ej_}XOq zYyfPSu@?St7G`=2Nz{1Ix$^6s&4oaCB=mIzn}^zwg5xwgV1=}PDLXTlC76?lX$eWntrsyR zfLW4Z$EmBHO7S}AoCii%#=sQT&c~ytnrrmz#b9YEEFD#XxDiIdh^zkRx#U1uLw)+A zmZbS58e#ecyzN3|nE@eP$Q1py!{}A+ua=}U4!=%Pz*GLz>9p>j{2OyL@s1t}EUrO2 z7cdGnM%y7*{&f6|+^V{ihyE7u4xkU60BM@h89jrV1>|HPTCVcOpI$eC`p z;pB39-Dv}-Nf&+1hoHYR5C)*S1+I2lx32sia84s3z=A*Y*k1o7)|z|Lq(DL(+r6F& zb0%q$uXvl0+r1T?r8O}UAQgafkv4XMo`d~M`sJeGYc_orfv4VwmdUS=W7%a;^&(Hq zUcWIt>O!@CcKO+k@~p$fQoi0gOLn_Cs)GYH@$y&%1f;^kE&cZil-e8ZG2K~Nfdz+# z_-A`e6L~~AVNmQ=*G@{7GBtde1)+b~N>+4mm5y%FdzWp$b%_IquhpGmTAJarW0>0` zf^BDy{by<_$tEw`HkSFmrS#qDzVDqc*R2pqn8!3T;&Ri~dFdd9@^dc&hjiXoLBzSM z8L*TkeAm;*w>uBs=-=1|`>(U#Z80FBBtquzHbQZcN&dtoZ1J^@Vd)CLMvDds#;1o)0Fq15FS(t9#^PZg{zJ;qX7bTG}cK6zsYew+7$D}&*JAAWO#S$Y*8utH_zD4XKN z4$~e$%dlqx-D)7lSQ<3yX*f(gKxbm&K{uC}yzW+vxgs~)kKc?HkD**~BBisY&b|p@ zpB_VU(}2%N2_rQ(>=i`)+^D?pTPx$%igJ*|XJMQs-PiEB!jw^<(O)znqnSU3dKr6p zqQDY79q@c446}R6e_?-})hGa5pE(GIwX~!j8j9vjv|cnZI+&pqm!P7Sr_J_#x$tn# zEau^-?5^`9 zxd(Klbg;{@E{F!>_h=26U2MeHiIIpm8s)w{k_m$k^z0M&Yc+F@YmRhIT{@HXxuWlm(xiW=N;20 zj}%V2EO4B5ODh8`C&` zx6HuKbYB(L!GRc9q@Qy!Z);#y(;IWt=O0aj^use9>y5XtE+dcm@`&5dIe2^T> zLqo=zX7KMx%tMxYFbBTA@=mbI-sla9H|CJYORC&joB6JxHjT;OPS~|lX0z#&kezDt zD^6LE1^%P6s}8H>ml1O~#IFVt#lxz?Yu&28f-wC`5dF{_Nvx-P+Fv2^QiqPcW8M?? zIX=E_1_cQTDJmi=7FA^Bw+6dwMFP_&#;YTpZwtD^r{6^dbpH?{n}|u@zk7Rr}U@uwi6+LeDhu| zR0-Q}4rP3$0AYoTlarHK^@k$7l*)9nm+(f4nUfeQTm#f*oOhz9UWt*SSN*N=+*>ZB zKNGi$5tkQNEl)1AzR#8gzAs;;qv-h#ZH@-kl)Tt<4=*~K6} z`I#>XEFRzQjKFstV!{pI<#7yqYy`{K)V!0F%J@L$7!;2l2MHSqLSMdpBL*92LuFBj10}Q_$0A=9 zlT(c(@d}KM^J56wggq7O^Y)d8imfEy@*p3T2gh z=MH2kPQXg6Hf>z&F&X_@VC{0uER)d{1Fko_Sxn@f8ZEbk*&EFCoGBtH1#LP$_82ISkMz=$9U4p?Y-Oe-;BAduv9Q^j0?!`& zD84tz&x)gv1I%I2h&+Y6yT|6HdZucJIkzFoz08T(^@U~18Xr@lIgAoH(WIKs4&@1he^zV~AN(N6xit8@t|6KJ z9YAMp9`XK>E|o`B3AdV#n0j|M4>jAQ>uQ2(WZ(e9fNWDJq0Y`EzR5Xf8pR=Asr6n_ zb49(R1gh<2RaQF0zxiaS-?~EN?fV;Qn?3Y|E|g}iv-Mma3#_z`AeXrbVfwq2{<|ku zV`*LkA3Pu_-Uf4``A;oZZ1v<@@f*9XkpGLA*-2p<%$?8Yq>d*>;B2j zk+Vf@(f1F8jq-XZ$M~tXne{RvPJ3XbXT>(IWn3CEe`bd7tcy`#P-AAkKViHzWop+YHwN2By>Wf102u5qJDFw_G`)5zoSJ2tc!6S_yBPM(&bU$i|5~8ZAaY6sAR`RC(dq!>4_vzeLA3UXkk#%4~C4~F7Xu62S!>D4pQkQPcqLY$D`fEIY zeLJ#-gogIeW!9^g)q~&I@R3v@BkLSS;=zpnp(~X@Ev%}#Txa1xSw6lITfJn8fOzdD z_|u{;ChAQoG{T4Ms=tY?YGh>3#(id$ze^G;+mSc7VkD|Qn*MevFO%iKfWqagNs)?x zxIN|(0IG?-we}x}6%2jE&SBSl0u%5MAaP5D)38JzUrH$CV0*(EW+iUPBSZUV*V_!_ zG)_Ku`eB2G>h6)NeYE`i#wL%=uf#f6)CHLc9{u(GW_2@R^XaKl2nbi;FZBA*pSpRW zQO#zKGyUB+EI`~$hgdINS6arL!HLEV<%*f*?ZaiYDW=gNOSkqx-{yt!HT|9`>qF-W zbf}D8NF!O{yGOFOjh_RGt&IBZI5xQOVk61p2mQv43Q0xB#b_{fNS9b@xR%2D$)@vz zaq`~yYba|&4cX!_eJ^yFR$2%u7w866sh^m?gy)553cxB7$qfkJjWpua`8L=l_O z3&Y-jEi3rR__=Tn4y*VZu%e}!8iMDN+%`+U-AB_qC)Z=|*MN&kG{?FZm{8hpBM~Ux8pCoqo{-oWiNl0u3NXM_Y z-iW6N3k3{)AYy4tS(u>8!1IAOdwGMX)sbz>TJyq2r(~Lm(6)3<;2FVzJ8LD#CZpsA z&ODivl!w{aJJW6$hPyitY6W^ywn@)>noP*Jf2hcU=Ha*8e7r^Zeqhn-3=+@-pNo!z-)d-Oq(irsIlY$K7N({~#z73>s`eyR(gC z98z-Chfhp+V3SfxmPSpCx1vP+5w)uQ_|rG#S~|WPoh{761*=ePr5*2TM>*e|M@0j&UX%+tIG&(^b*s#6EmENXL@>;R4;FhJ$(=!Pbf+k(sUd8r`Nc=Ui)QY6SQ( za{9D)EH`QN^v^x(I`#&wfjn)c&j4l1d>rdmY#meI7w30a*{s9eZ z74o~zBW$j_t@4-7XU4O8bsihidGz;1v$FoBL7!b0st2L)@p0gN+Wpp0%xcAfgnhBj zVXisM<;$wRkHSkr^kn%S)*SZJ#wwMRKbVe74M5E3^C^9m)&4vy06ns{yFd9y5oHkKZf_6q{ul7OflILhX$7i!U(Z+eQ z;+Hn%a=h&vFIbi{)$9sgT&%&HaX>h_+@y%j{LXMB1sw*3x!Wqqp~-0g%ZRs!G<@0g zXoPkrf+b*YezJGH)0C3ZEiCF94HvW=+0n;PFhjuGRoJ67&4MDl|Hfv)njJYbXs$G` z@fNdn*eqdD#F-Z7pJ}EBipzK=me=F?TaeI^Lkog-3+k*if=NYH<3r7}MghG0+2@(h z&#vA1Vki>ThyNC_@8tAr5j&9>>ck;Pl2K3Q*SkLDm&|Y*u~AW;+b>C$@wwvqg(8An zlxiTz*oTT*^sMxx;5Vfzq#pyU!HqbJ4;63rMeI9zR9gefgMGd~)})nPc%2;cM+@-l zMaXi_Sa)tu0jmfK#-rukU9b2Uy9Sn>H3oAPU5znFA={loZY^}fI`UgDWgY0=?J5xr zpS3XCWBrj}EL=HVT>6&1QWGa1F!VS_cbbL7iiRPmCmVH66!KAWbsp8_{7Q|D^uTNl zV?0p4;-{?jH&p50@N%ovl2M5ZqoofD`Oq&<_RW^1uzEpzHElS|4%^|5hpKVWIb^u` z?4c7$Ugw^>6xqh;^8-jE+WIWo+Nk1M=y<<6pOE81Ss$s@K8c^QHuduNCXm1qdnRa! zKT?^ZG4!u1CNrA_Je(0RlV8D*K!SU~{w^Er2k#I={&Y7a;l)q*xbWAsal`J0j9<+IKL1 zdo!dIh76bIZ6YV?TzN~bHlZ;4J|l-X_f}fW4Ra4{C>nN zSS)ZTRir&08W93dprP@(mqZis>J-ZHdl!yK=YUV_VvA-vCX~O0CoWUK*8KNhF%VjV z&}3kX#bR-$yUK_viupRPYil!M6fvwW^h~{705^6XI>ADnsMR(V;Y&m3Y^%`$r3S8V z4w2*mY6kNCb?N%77Dwary=0+MOuoA#ijb#f=9)NE&i(IeZs(f2B&Cg$W14GJwS zKKE!<p*z?R}tKOBtA)(4t9Maol>KSuf;8XKmw!>Ik}?H3u!olmaa<3G#whY3qF}^`c4eUK; z^HDy^Qv2F~c@{JVDyhS?f)o_Atgeqc9~hf+X-n4s?oEF?vln@KNCqY~5r>s5o4t12 z96v9x1VbCx>ZEwct;rgnG#b4QVwO&GhIVsCz`v)R$CsKcLLia>;lNzC2-~hmZlj2b zYnOvYq?E5l`T}tP;ov&je)#}{Tn?fQ8-fZV-_*l`WFa10|IuRDYi~O(t z&@*DE>bKJCRDY%cmfzvI%6asaMH57>=xcjy_}O+cw}uFU{|s(Vcp5K+Z^tFm@R5$cx2|HTUF;QQBBrB5ySv>&1qOyo)gz*+23dNAW7BTy3NUP;KqH20NkC% zYD}Bm?)Pcip18yIrzygs|FK!A%VuQZ0Izzqe}?36JNwVBn+Z=X&;7~r27Kw?s!=8? zni8@}zx^pMwbFHF=JZ*vji-8;Lo-9%jMK-MfKRsFa<{Qus0lAtt1T*-nylVxYVyv& zf|y{2hjG zV_i;Day3l_D_rj^S0VE(l#Q1wp9RX6-aEc#aqZXahJFEEM!S-R#E3f6Y`Ye?%WiLs@%)F^26#3RF4>5wM$M_gQUDOYwu_ zmcPfW?F^#bv!W*D;vD1AEFCGWB>oJ-bR2h};u8OE4+Nkml7ta0m+pJh7VBCPE4 z?JG!Z2`Xz+U(9NWfjKte-!a4F{=px?ol5JGh2C|g)0_c4>Chq*kDi83uX!V#3dN^e zH(}jX_=+QFY^DrlP-Zq|FtMJ`V+5f#db<9gI=;~#lnFj9`m*{*VfOsgCdz!o_1}>p zkc%e9h^#7Em&IgfJCanEm6aLJhpR$~w%Ft^qE@J|06TlNpJvmAQR&5MdGl?0Tr`+c z!Rv-1gRRC@cub7ESCC`sXLo_{H?U~buwX|sl7PctdSEx99(ReU25p^KMJp>^T{~7 zhxQV2xzc?YwP|Nm*{Snl`eV`VhRi^1+r0Mul8C>gL3&L}1lxzwa zhn2Mv3b111U`u~>xVD#wb7Ya2T%WqqBV?$cV){W`ukh;rq!qUy<%|d>%QJjb4nwZg z%z`U9cMy`tO-|b9b(?rE9&qE9M=hpYd0w~zDJ>-ULbfatc$<7mHHJ5s`}AdA!_ALY zW@SvmQlOiTg^LiTN$cL*;z6BP@0X|Zv z^Lh@4$4S;aq!i)AL&e#&&6aeT?V#~(l(;K=1Xw~h*A)o)b(F`)@?{1=%gWC#<(FU;^hC z3nkr~fS56NZ#>XLy=FB5r#hSr2xz-OX>i^8DvhSdFP%K$FZG?J_>lAWOKpa>k zQkbK$GPZE4wRG|C;;P1Vu$=L46d8)uH^F+zpIa$G5WhZ!F6fSbwn(S)$U^0+TT6tn#5ge)DT=HrokXWkNBFqO5VSP5!d^SO#d=f$s z>UX>xoeIHPq@(r6{M4|wGb&2;vD&3PDT<)Hr`H`gsxDtL*s5b{H{oUaC^^fg3*v() zM$rt7%yFDgzSKW+V_Bp{)-2T2Ihln34Y4z_02I31zy;sJ=aJ1XS$`-WGy==EL@|Qs zqhV-NpaJ|g=yY_W<l8MM zA1K0b+j9ofVc*VYZ3EFd4_ZcEz88JIvKsM#1a};x+?r@yY29~?FBY7@8q?=tbZjKm z=;}bDbG>uBKf`mD>-3o~^n(G`Tmx|jq)^{98U5YB&?dXvGo<~Z(TJ!!dQ@lX~ z#dhYdP@iwvg1|*|G2A8+Yl0&K@{G98uqO9cY5BE|FB12pKs@>KXr z9X{&Br6&I)7)E)LZSRSWRA>wT!H5`7Ig^5%1^mvm_fUaf}X#vgf)PvJ6w$6aLLfVOZDIx~<{gQ#qAP1IR-La{UHzfPGh(?zhON zCm3rygI~cJkbo&r-FL(|jU*qzceg^VyzV&O8<|O~=*aoFh$9Q1pI0R|*+` zeS$Au*qxm?9c-;N2&?z_JB%7JyW?v}J6kJ5ZA*6q5D+#LA5ph?9WFCN`W8O3(!L}5 zICNN9dcqwSS8pA}3n@Oj5$Ph_QF3%cXLn8^H@a5ibYj$=cJRW`@BWu?E8EdzbidzZ z1``?jPTty1v6F3AL?#P?4%NiL-XQr9FPXncvognl5f2Z>Y#iBaZ-RZXuGl>JM6o>E zK*sHm!0kogny?u=V-aMCMa1%wACo;cnqxtxJ5wzGx$Rq~lr=p6413y6G6c9r`(CW= zU0WwLrGfB~7*8!UD~Bnz+yeZK=KuUzlOc;_kAEB3)J{iGI&n# zA^lz4P9Rh6qw#m2eYNIzsk4~0IFE-ohF8rs`mi5sX7->o!C(va>j~e%1pE12dMW;P z=UHag$WU&!fx5ExoC>WNUmg73A_Tgqj8%u@af2v)d~?xe7v@#3OVXDoJKmZy{3bv8 ziZmgCAeJ_`ou*xOJOND`TsC|xz+rZXiU?YU}k+qNFBXaw7ihyqV;c=oy3VOW9Xs*#cb<`^in!IMz{2CA(4E zWR{*lE}7rHNfHK$zCeuzhmEZ*t-E%q+_)PCaa@?7H=YW4@t5oQS@#0q2)`cS@Dk~h ze0OI+`@oRO#UA#vw~ve2ts0Cy7^wDtIp!%Ekd&_518v+NXul={XhgcYIg(w8N_Zj0 z;QN^tiz{~irRV(@xB$Og+Aw}1?ABswMsf{A8808aN&^@%akQCgV4BDpA)N-@|5ZVi z6}hMEMB9Vw(>Nex=EPi)(gVy@|)BLnk{8Z=F2Ic{^OgA7+aoLchZ!&?u5NR z7?Nv!q$;5jDdpP2_v>N1DseswXJ)fi2y1YC7ttPqrA! zOQV?3eCr*S)+qBvGch^?1@|9!h1aQPVjnXg;1T!T#R5;ddrNH6Pib`O-dQV7MIni5!4&L@A0pBX3cibZD7t^Das{~=FLgB*DsM_P7X}AdQHhR?r}Dk16&YKq zBtPL_hv$l3?hsQejpfP2giFtLcn}hkc)c*RJQsMBW%`IvN|M~Lf|x?DLnWv*qN@ly zudzS)INV}l=wP$TNnc-1#c<`Lz^R}k^uLnAcdbtx{K}P)nWZRak4J zfIy6`6Zt_IqtI)msWC+kc}FJ|-(m0aHsCrWpbI<`?w$NNJp6uW*mDjO354!VhD9>zq-gc+W#C-|CalEY23 zdQv?-l#2JgJl~MU#kHmF{_ik(z(HK?t91fk=yF!8vmVDcEO&7p6A$9Bp?i;^Bby&Z z1~w=!J626!G-)lc*RUd8L|h{8?cEj%!LPMUQK{eoNR+>T)zJx~ds|9S7r>i+$#l$AuyDzy1^%5)vX!A^sg&_(d>9A-$}p-}8n185OP`W;3oO z(LFlf%9vBs%5mNk&V{5z?L3qbu}s@&_utZ19HsN}e(iVw9)DdTKtevRcYGDaDigf< z;jtoYrOt*Tlqk2

+L-An?yvzdc>TOyrA)^sI*`etmZt4;y=v2t~pJiDP^IfZL<~ zavQzwtcaylsCGhA((&CxELL!|%An+;#QC7GpbrW0U}*oT>6)1KZ328?L3obVE?Ex3 z`;tfff7qt1#@D;JQjlsMYvE)2%F}dT5y}4bw8{gNeU8D9J;S~7m%(@KjHaZuX`Zjn z5&BM%R>6}D8}{!X|D^}sT|xrW`1s4km~2{5W8!kjg^2hYC-xQ37c1!J-9@<&KDNLN z=W;o@%DvY^M@vJ22u%wAAT;drDTeszkFwb@hs4_)CLV;D_y2PcP--^rfM(G1tF1x-=*+dwzU zE|AU`&oOhfKW>r&KJ|1JE9zmn-twKGH_g>CoB>NfmS*Px(?mOl?g}D|i@>43vI@<` z_z4f1HT?Qzxybo_8q4INer-;W1-tSecA_+7&0HWjc zG1t-w!6GoaH!oQka7@^^7^Csp^N(kI9$1zhj&=LZJz25Dc@PQ&2kG28-y*Lj%Tj;p zM_x`%$pe@J^Wk4w<8G$%322h_@h>Q)`e^Q0_pZWZ_&SGu9gz9C5X{lB$>AWVC&P+* zm1p^$?vtiVwV)k$`Q4A}?SZLW#hTa^@?goAzol8-h$P)3{pvh64=6{B%ca$954gkAcsbFZxlC;TWdBRR(L@` zQf2xIhnr_bN&i%9d^i#GxGL(gNPMqQzB|JTR6s~khykDw!6RN?_LFdbb-b38oVn2D zW&7BQtkVoxBDh`!zD_YS*o_85z?RY7{N_9l?UNEyiOZZ)ecglU&zFVPF25F8eIDEi z2BaVus-rjd4l%T_1fPg8le><)b7ayzDy3ehFt!|h0}Zu*q||*f@58d@wOK%;G}Y1s8z^RUzWD}d`b?I%5uYAT zB~c9@T&{oYJwG^t-DU`KiZ3F}bnnrB_xg%@aAz67d_Vh*QExHBl$+gc#cIrz!e_lP z!_Mi?kbaXtp%+j#5cDxnF=ej>VAxER)Y-HM9BT{TB1tO$_8$YeW{!ej%br5p@;^kB zt46#}Uj;FfC8SsBdP#)WjL!R0qvo(1KLCZ9-5!*GX@Uoa8KU@UYzjM7Iy?qCaP*^C zXkXLjKqe$QE_K~1D53WU|D!yW9OuK5tbx6Q%c=}eEt3ToCiCWS(dVSl{kIw*BxyP`SB1eaq5onQt@Lcbvddsaw%ZNj@9 z6n9#~A$wthU6BcPfD$BROAFIEu(Su}Uqgpo}knw84FpR;VBZ;xB}GmX&9U@N=WPO@hc)W>Z>A zJvw(qx?J14P6^g)vkXl{uAk31aI!wWqqaR{4cO_d7OcKvT3tFLI?jv7n<-m@XXygE zA1Sj!e;~N~sX%}OK2TmgF$P=>JJU*m;FdT1&g^W+J?tjP|9tv_u)o}d4g?_li~XZK zIP8X^eB~cCHk>|SV(r7fyV`R4K#KrW#=IEu*fLCygcPdbveyd8&g&uEJFb`2fi*t1OSzCRsTe<)5&id19VxDfSk$vqE4M(E3^ zVphmCU_+nvV6cHF3$XK(OPc3-N4P?7xJ#eVFCN{s z2}6BG)e#H+>hmQcfJ8aU>V-W@)8a$j+B=6h~4I$5+dz54HeOqnA8KVNa#8MXuFim}- zB*fWjG;{8<25Ygc5d{E12jqLB&M#vvpIU9MRyj);S6xrdIWVdLjvLY6|7-p2)-Btl zvRwUb_m;RyA_WXxhT8hmsbT+ft&dQ<0q{B?czG~D{q*Z&Q3*OgECAlC+ZV+^4WtYG z#KWCt36qCd6^-It9)eB-exrqj48Rl$Ef6LtAzn4OTZLzhs^JG=Pd!2L#NC}ic=W%9 z5FY(GUIEFB=(Fj^W@zX;Fd6(iR!hIS<`)8;Y-#6+Uk`KLH;c~Y3^|>Q>h6ebzW>t# z1iu}Gud;|*Oz=j>l*&-7(oW+^QA(`l8(9qMN0ZZAGRc}4q zGMrzSWQ-%gV>RTpio^u?uJlw0ecEp|p&5d#>>8n&@vY@w-}LEck!HV~C93$OE1@M0 zkkg}Zh{#<3#IukL!s-7Wy#=ikKhOY3O&97v`oJM+um}n`m;62T9pBncrf}Oyr3K@E zS5Q~2(i4ByYm*H_aW6jJQ02kV^27v29R&z?S7hClPc|j8kvsAg*5Jdz*>9|Wvd?_H zCK6t{fLuw_m9C;%7km`M$AJX;mYs2wzbmd1AjI)QIyZ9&5(5?E$oPD9@71Zn*v%Sj z4alYjddk0l>F;l}g8z85cC9@Z>K6%QsE$HgYtP3O)@S*;oLx;%28G;%J(>7KOrFk8 zbkIHR&6X0Tm!qB5;@3;7toy@$PT?7s1wE8;%r;OA|D>V7$@IbT(L=$g2zhCiCK};` zM|7za#dLaS`=@-8x9^LtS5KeE`2)1sD1y;U5&HcNOXcMpu3%&2oW8&SP)J0TOzP&H zPc?vCV}mi^XDhktM)AYtco`@slwNuqso3yOnvhR`@qq8!6=ulcbMah`-dr9B$E8wb zzjh|CZJHfaQNYrccGXVxkG{8t8`Ud7}r`$6O zK4TM(_&4_z4U(FR#>_W78Z?)>`#!nq-dsya@^yvPgtGsheG@`+1D%~;@?%9RGz=wD z@Hqdo4e$WF+(|c@KSsA%Y#fi^V1Dz!KGPFphh1u!&9aK<@Dtk+=-yLX?_l5Y#{u{S zzM6krsT?2QIjom_`lk}KkVny2p+{@(KE!`Of3(=oKv3Uq?+;0V0Hv(;wj1xwXj)O! zN8b~_@8^E>&tWb>HKnW>Xx^ODQs~ zHC{NNHxwvjOHI9Alt2EIdiIA$c_YM}x)dq?wXP)N24v4r`ZntJqx^;W1fhayf4A&L z$+FYEqusjX-w(TV6WH%LRCtj`$B60vc#i9HOBM@gbInqDlYEqP1?dXnlc__jA7c~& z(T%(;lasxTE8?Ttj-PXr3l$FS1r6dIPUig^8KP!e$@wrddr=i09aJ`*K7fhw?(YB5 z^o`+lbzRqKY&5oQG`4Lvw(Z8Y+1PC3#Jm_R%;&utvON( zHli?MclbGMg5nk+Z$;y%jYp!pp^3@i@s`B>8U>SC?4g94f1lEY@P#4M(jBc^*)y1~ zd@a^f6#>8d0o@>C0xb$I;*W15AxaEcn4?-4fR==^jrk=~+Rz@-W~msKA6ELWE#et0 z>qS_j6!Hmp7=jBZKz8~^#sRALzOc0E`qGz9aH!X*O-(m2C(h^Ht)6;hKM*4$_)mO{ z!HHG(8B0Jd{X)#^rIG!&C_(_o|Niv1?9Z=a7G=5a8(bc4sAfP>as#lvepFt{0=%vK zC0+5#Y4Gt-=iKpy|4x?X>6v39vOP_xzk4P~NCH_RRuxg&_HrgKchCTn1s+dx;fXTo z{>QgKI}ZV@6&W>mf!8l|x^Sm%-FM4O%{*(K^mkV7-xqa~Hio-Pbf19=jc%Z{o}XZQpKDKt=z0Fw#;&;tcHb%IKN z-<8nfvh;H&)hZNnVF^6RGBNeS_W<<(@&FO|7Z>i3(wxzq9w_J2+o=T$1AvgX--je( zxiH?B&O89H-;N#Cdip+K@7KQ+9bAXEnFhc={p`&!;_Rzud>0@B`8~rPSH+cWe)O(W@ z%ocMMg^>T=?lyG>2sBoJo-qHBIjO<@y*A^BcFNLpyZ?~u>9zjpaUJOu*IfM#WMF`V z&>LAei9!$fv3c7eAQH8uN64RgTv2jdmb~uIx@@nOJTF5VffOiLci9ypYR1YHIw0w? zupK|trrTS>6a)|ezK^hM38efdh^rqQlJZnYBC5gc?a8;(3z4h8_!Wf_B9jbmXn2BxTbbuk&u=T{Ep+V=NN+bd0vB2%HK{%x$C0n$&I|gz182)UfF-?Y zZ!jp(T?z;g&aXplUtj|E&RDZxC7adkWI3Q>N}7%qsLt*mqely1&Ahd&1$pNhIG7ZH zAdn)v&jkP7P8QyG=i2gd1SvqOV%7Vg3uuFUFcB1;HWCN?7l1=AEUn3kai-S;g?o^Q z_EpAzMDKNRZkluIABX{50L?p*PC$CrX> z(0l!Tx0QUnRgU`yl^ByTDOSjTaQeaz*)SP#eE*lv;+;df6W5P5&&k$>HCsrlh3?^j{%(4p6}%~{tu8P?5u%S^8uWH4P@=ggFHfYk9f@we&UY}!$fk?*VR&h%Gli84wS>r{}pI#s7>##oJnTq+JrBjlT zqTda<*$YD~B(NZ_moR)vRSKNVG4Z*}7O@J-a1x7(e?lk1!n|JkZSOtbeh~X+JhX z?nZUgX6uN5ZHf*9J~ppmqc^#?Rd-ctqPBm7AS2&&KA)Pmh@{1*5Zp%bYbhzUDQLw#jdP!kaTlLqXNeeiUAzW{WfmA~SFr;)F@9Fo|S<9m3D~%JcLI7J#zvG=%>QkFD(6Te7)Ab^>q#0ON%*;H7m&Au;Q1 z6KH5hTJ?j2Y8ok^C$80GFflwW61%??(KI{P29v30fHS|k-6_1NNZi+^%B2six+hJb z$De`8^(&cZ?hSPp;hJFalpJssa8AVDs+Iw|9inbI4)lL=f!hNvZ2ora%l0IB@3&=2 z7b@81b#4qsH^AkcS@J8LCXo3kT1^4KE7qb)+aZ`N5mC1+jz)&>94eX7Oy>kxk5uCy zUtZjmvlFZW^eAt7(cM`YZL$AtykYhC%w&#ONs*TAfTD3RKvcGJfK7lU2%_mgcExl5{C}#CdBl@8?Kk6#d@XtTbbOsSFbW z36k$G;UyNgWl+0@Zbm`E1Ce_ za=)2cvOH(d-=4KV+zKJK*$N`N>`sH@p2yaL^86>DZ0BfN4tL+d(Y>BJd_Zy^=t=F* z$FM%o0Io7THy>oSPzU`9^T}V+fXd`cw|8+J1GL3P9KmGLyM}N7J#4@iow5dtZ2)d) zXk9gsR)IzgHpR7C1C+LK9F5qcFIo8QZ67?TgloYQ7R1vg#x|owcFi`>6z|I|V^$Vf z_K}gIK*0*26L5gqXmN!~_{&=zp;oFjJQH~ENvGH!Qzc~+c9Tn^l}kdUBZlpDYXZt{ zlgbVMf(vuFR1trKoa|peh5o&ZI%rUEs7fj5I&W{kQmSyy2}B)!4u;&<@Q6|(!9}#C z^pXc z%%w*)Tuc;T5C^m%Y}Y7gdjk1Sq#M{`PLd?AQT3YE)P;ck_8N&R!-g4`ofiPfm=+^e zs__>(<4L71sm06Jko#LmEJ<1OwmzEdio=nj9JaK-EJxv@+-6A^h2 zFX-Lqpa7t719n>A!Ay&;jqD@7Jt{mj!^1T~Afp!^s-W&W;=A`s|DbLt^O?%}cb1UB z05p=1t=xgIO-3QNPMmVrP^-}wvg*2Y>FUgb9yy%9jsO+tKLE(|Yh=BbxNQ?K9b9pN$1m+xIoZ8CbZhfhVruWdsMUf4_Cf&MTC#(e7M( zfz!8r4Uxi^AaLBAX*Nk93joMX|5)PI3rj#V3|KKxQzZ5NS;Uz8txZl%ZC6m}6Fy`e zc>*t_XpAEfO9v4P&0q1_40!SO=8K5G+|v%(bv=>NGD5grvIE?AW>xh_K!A+_*as~D zS^zvTB~+qZAAMJv(|Pq6P}}vpA_eM4Re&kkALpgM{osj}uy*-2U+FkvR7)kBnJNV! z{lFLmU~0tLcdbWJ2?OX$9ZP~gNJO__IYrNLb#h7skb-eA#u)T;R&Rg?0nCMn*cwop z$E|g00HELVdO%i?uSl4$ITU|l>w+nd_19`uiQk&bKFq+3xkxi#@N28ylnkwTt;Hrz zYkv`Y_*~}@sR0`eK&lLnW8}N6_G9_S{J43uEJ7zRavA&JwLF*l8$?*Hboki{V~008 zO|Cbs`I|)~EVUMxQL&nbvUqz)?VkLcInI-T_2z^CMlS$E*A=PH*}W&vu7Y)i8X#CL zMV}PuS$Q~%Dh*L)V(c(2AK`8W_`={n8=X%58e54~NWB{MRdZ3IKjCEQWW=+MBg1=b zbNKriCoZ(z?TeZ|7Gb?JWcCe!A(RfvIS-rmM4{^fYscjj#j*PqJX=f){VDq=ou0P%1t7zE)&3LeW3}5D zj>s6`UB5MO>k8)0Y8DJ5)>cjN66un(awMeGxS*u#mXsVolqj8aM+L_-Ktv0_D1qee z0lcl5(|#+V_OeJOvH*dPn(OyR`IiU!Qb6+@E;@bx3NgEg+Y zp#AaF%WTruNnZXThCBe71l-is7)7ihysg2tNv-zJ$<#veeWRYX{k)!)_8*3(#y{${ z7vJ3*zNgU;(FE3Ak`a>;pDs83^z`-PrKAJJfsO~c_3fZ=cACuMnmU`hdG{7@CpTlJ zzX!doS2%E6{bYI^V3vgm_1Fq{$p)w6$*+jdCNIt3=kaOxEDUPncrdpeAIZ~SQ1+H> z(B5CkDImcwRZ-MF-5SJw1&B;hVFVSs&ASiYx=^&C`N(l&MYRkXkEd;(IW}x!`*XX} z=^g`GS5K!`i)qA5^*-hi0zba!YB0%Jn*Napn&@EyCsj6`hr*#ezb2}63H1Hwtwyxf z()@4PNEqf%#&EC~QU$K*faz)gNQ8{3X<}mHT@N`lAk)A0TzB6dtvCEgyPBkAX+H0m z+8TJwGplJ(AQ1Q}4xbuJ6xrK6YnXhP%u;;;cd+O;^7Mt&%gdVX2g+Qq>6p&j0mp#% z!_TxRM!VhC)9;ODoLI~xfXxk$yC6PQYn64KW(NaUxunIl_eabdz^tI6A`u=xBd?t|V$=RB zG!~wxNme^=wt?bqQy2Zt^P#haO#`c$Y&0CB%^}Zb?L`{~p9HjpWo@lPeptRplBz1% z<7UU^zQ1)R*yd}B%UC8GEaW|1P+VXywg~0T>$5^lgC{-x3}R&c&4Zk0n-o*obuZi( zNO(zRQ|aa@ULJ_R%?Y2tKlqtX8%lG}wT~8%>-W5WIr@;Mf^v15bLaWPpj1kNf$(Md zH(#(mMa6mk)Cn0Sle!|F>VS$bSHrYSxAM(4+&WGf<2nb9uEyVBISAaD%~jA&eBlD|8&34rCp5>1~*6#EX^G?yvM;@ zl!IZZAq-YgN)*qyAd7uj@%0QC*VI@HZ>@{X+OIr*{E%)(!8IC%UYX<%olOdJE*%Rs z%)sguqb6USZw|2Ne{0oW@>Yc0zZOpKptFI^WWm63m;Gg`d6ejU59zK-+ZXT zuk9@PV{43Co4KQ{R-u+6gRBJ>(6+Vm%4Qi;9MyZVNQB$lA&gAF@&ap%+b)nAYL+&S zN_uum)aWcUrLF107cY9P-FF*#9GA0>U?``$v}FsuNX@fwjOsB;{^%K~%tt%)F$|DI zMpl$LRgJcklr5UrT6wDQ-oR?!GeiE<7LDI zEDz`~pV0Yof6Uqrq zhB*8%$9@!-g^oD8474BghjAh)Glj;{1RbwaamN}#6;$KadI4Cfp|b>msq$2e>z2zU z6u5*w$pZtJO|GX+b0w1%jo(8L5Qi%zwq*4IZ;y%z0B#y@$X+ss;51^s>HivJuPz{j8Xd%90 z9UGj?AyQtvqQVNZQ~C{+MWz`4TdN6aP4ve1P=qFq@AvQ6tQ3QH$3pU41ArJM9%NGsi5Q&uL$?Yu5O zJ*>}%?xq-wX1kT}v^ax5mc^iIwlKnYii<7HCaj1E(m15%f=5TeWzt%;8ixC17$KP8 zE#tIRP!Ih+n*!Q-@pZ$1$Uy&-6Y$MXU)s6Su(B$7Ja)GpjMvdw?6=kTgsgOa$O6X+i57t75!l0Qnn;zZ7?J zj=?`Wdc_lKaaey=)MbDmitD6VEj!F1s~#~#-+Fp+7FJWOxE*u%U|jtv*2rqzh3<8y zV6e_jsiqdtp&x;atS}1iI$=Bg7ZDfN&=&vK8i;;XQqY|QQjkil2-hvRbm(2F$);^+ z$p6*=aYR)gqpy-UaGlgoT@*Dphg}p&AcawG#0MO&MhJksJi{FyGJ+de=y6r9o<5x( zGS=FR{g8PxoT0@k>Dk2W8ZC^{H*}n{0+|h!U-_$q4gu_Ad`!c3&PfMmiTS4^d~9A5 z729ST#4L7+!QUccW8s3WSt4v=169jcE9=1b+0;nOOP^N@(zq%-pwsYOx#cGU7~rWj zIbwcS>#{?M+(NQ6+F-R@oY{tK{H3d>&ZO}Egr}lCi_rx(yWvc!WHB1Mt<%;$4jRS@ z&)(<^T8jVJP|0*^_5k62aXexCcb7kB z8tPb|x*T z^Yn!ceF+y;&62Mj+ARtF^5+jCyKSBG$1@Bp+~dV}S5EMd5Ek*0KlAc(as@*L$w4s# zQR~1=4kk^1qcv;?Ng$(Q2Fo%epqM3KP2rPjoyg0d{No71MORPN3$J^60hmC8MGDS6 zC~UV%v1RA6qKK<}gYDo-y$$>Ce?363<(3IgkhKTg*?|2D#_gfkPp~Kb_l0{RCXOxt!~`9+s#$HkM@7)d|N9jA~_OEkhhM$vGB*DG@ZO#NgGB*Q0A| zyD$m;faPitW886G2{%yq4WEOj;GDh3+Z=<*3{UUM8_p_%N83?v2sBOnG>i`ab%vT% zQ}c>G;^wVDL<+gc={1|umSuU}?CeST<>QqULkh;JEuijDR!=QyLR zU}Td!wbgRy)bh0R@J{&wGCUS)uMmKQ*&}e!y*D$Pk_Yvatw(``*Y~R>uC~sV6csXB zR1Hyf*YMd1Gfp5!g094AJLKG_V)Ee$vpVUoitLR#)7A3xtnL0^{m-|z%9ox0Z=xO747rEC{8HY!kbXEllO3r;O&JuAm-3u{xI~PC- z8I~juo0Md%sFt!;kDgA!*3cb^;Pkx>CgXcPDII=452;f(OHQ&K)uC+as(@8lJK^#V zckiCw|E(Q^o=XmFE|$R(ImA?YXBC|_5#~2X((e6aA-&puJN%P&M2?~4d56m(g_*CX zM7Bpu-)P&1j6SEop6Brq^j58e7pZ1d(Q)q(6TIGhyU2Ov1nof>(iMcURM++&+p-7EIT|@=HXKS^LXGd^RiIi~ZBeFdqyF=Sn zRrO^QDX;d|rqmrdRzsb6D7qy5nfeY&NFREu5HMogZKuoe?~=;oSpCW63^G>|()_SO z->kE0r2b8fbZFmL&I`ZxPUEGt-407DWN8Wfl)Vt1D!+_M?(>5hpw|Fdx&>&Mk3Anf z48i_wgkk%*TZzZv)Do!ks729eZu5=v_lrBz#*=sg_2!4y9hZNAP=-VK+(R!XEIp?1 zmBE-_QvoRF`MQw;@FK)1iLNMNeP`;ti*>0878T+@yFi-OpYP$CT)IW3q)@tjI7VuV z;NM?Mk2m%8^s}>Znl`>mdwM2fvvOl|*1Xn!t4$yE``9I=9Wxn@&xz?uO(|AX3n=Ig zN2%>ReyAtJW+DnHfmx_}58Zu1zu}#IE~K7?mFLNFq8rx-^?Npt8+D$ZcfzF8?CwJn z7(bb>EU&6MC>408R#W3K=l=#D)U@fF8Aj-v?!Y(tfT z?NlKZET*0ZF{{~l_x_97>toK&bvjTevtsrUc-PYJzA;--S#;oHed|#Bm6w8^>wa9o7Rr2jGROa(Q(HOnOKi=&L zY1Nybo~JT@v{_)R_p=qRju*xq08-2e*>vQd!_%N_6ya`M!X7?_oRdckO)@Gel2Qj=&|@;%w>baKB-T87nARX-}`Kx zSxWApZ7K#a<*Y5@!iFb|d-nc67vS-(n>;U5w2)?sFRgE_MGx@WOi7YI;i)3TzebLu z`w?P;r_;U``jVDrxQ9&rRz_8y75Rt?h;;e8UUiu_EPta5#T@$7cs%JRg ziN~ql)NB2#&;MFeP0cgrBuWX7s~%8*vGceFQ(GWQ;qmN(O{WJjMEGZHfK7~i6Se#D zZWhgwJR=r$`WJ{;l#c{SevMg7l3Kav+VkW zwMG0}xuJmJMvx&DfF|90(`=gcgCWQ+Uit?u^-5|fgOZuvg+vmqi+-)YB=)(=`U%I<7!Mm) z?Tr7HDd~9br@Xyi`T-QqYC!XlL(1VkB>h^URtc!rPk}?2LL?M^yYuxzL`|)#?SdN* z5vscDgBywO4p{);*37tOYt@@2WM+<8mS#6*>TkLO8*x7bbD_}E>*!;K`~ypK?Q|#3 zfJB%HC7+5GDa`D0zV3fd5}wV{d7$t6Y;vj_%MX|6wo3-Hhcg`@qarr~wGR#bUP)%0 zug5U$3x#P2OWTnGL$E*xh(d?h2&wCuwMMhyi=;1edrTMo4+s&gx4mY#a_D5Op3yMq z?V3>tO!%EXBtUj6?J!0kljUiK944~hS1OM{3hvXTLKQS*>@-SEEYC^YI~aqwP~~dW z1Q+Z-CE$Jw^oR_dPno!j7#%<+w_a7d6A?q&2=F2b*`xEXJ|PW&gbuVTm!8K19!wq& z>hl&1yXFz$OBmq-!_I;GhhzX{HzS3fkeng8mA<;F7Ty9dq|q@78&}4_fC9vLOs3M| zY5Is)r2^=H4Cc4RiZ3sc^P9s%1oqekWpTWH_eR?~b)@j;nUNJNt=39iEd5L@7|90^ z2GQp{wa;Rq7)e`gbIMv}-fHPExB57XYMCd_E|z^RMu;jws2AVbw86T;+@cA+vT z^tJDW|7}WOMG-K2I;FQ=(3l-7FKX=eJm6(QQpN^A$ZQ2oxzm1tTygQDneWeF*^wqj zYAu)3KTv0K@HFp0h7=oLkQ|p6PV4%Y7g+r)lZKA7vwEbTx=MG+D`7GUo%@!2j7m1%t`(4%X3_YiX0C=M;9?3hkNV#6m+3eT?UIAOXba4ur1R1;28JBAk zusn|LmMPne8gsdYWt$-_{$^-&YF6}KmwNAU#xPnh)9KrDkD#1~7Tt}nG1j@U&gAV8 z2qc`2UHa+wTUSE>Q^ko@d-L1XO^n;LE}OlxdiPwNYW*%YU~6K4ehD({+gV=?Ur!~K zH!qD`XF!y>mgw>Y>WtqL;+(&B9^LKR>86rmO3K(mwNZqJTQ82RJoQh$K&3qG1|jhi zF*3$g0`Z*zU{EaHPY&_|?=A=9Kl{WmbsPHXkObbCNF`$TN;2(0i{^$lKOQ(bA3H9$ zA74EWewwE<8$+h)IKhCNF8tn2kRae9+5w0%XS(s)+KOg3C;IK$DT@IlS&?65#i<_- z3^kA{=KlTZdwUC}@+uUS5_UGcP6765e|G@&&8=x_h=iNo>c#pK9;$#(ki=wHkfjLagIhWM4@s}KLCaFLo99D4 zd48^bzQ@0;E=RH1f>66Hzb%!)S!^@|4g0==1PkK;M$tn-NEkQcb6jh#Llp8Ec>Tvr z`xYU{PAsfK-*rD}Bis4WzOiaF;)V~OW&Rd2k3{coPD`ht(>pVJxsyhNsOoTo!_-^y zH5l}kWpzFq&^Vwtf+SO}X~oz`hhyxd&3Z?VVu-hWS4nmr$0Uk7-Ow1WrX0JR`5`?kIc)pB8DQz0HkK#>udw0~!V3wHDcO3qee(e>o? z^mwtFaC!OWz`AJ_o8OzWQlomq@;L+!(`m!=(DuEnq$G4MTHepM+qO4bV(=1bM!h*UW;s^Wdh*8D-7^?`e4LmVHzz0f$f&t>Yv|&+>6M5? zS>hM;5utIt=rlNr0`Mdh00^tCZ0uM;f}#x6Tfc70ALCZZN$Sw*>};~90~R9WnOjfG zp&i_Yl~tW1Q1fOvic3x(y=9I$c z$8k_zCzXkT1`Et}@-IK!RnS(n_4sAi`|)HH=O_3cHHj)w!koUy0rs4>niSu(Uq=0T zh>~QcL|RNFV8h(P)7Sy3-y!{xF=C^*CJ?VSLgmIj+Ah4=XA> zMV1>jve}&Ae0Ks2a{Vd`SXkJhYmz)I5XT)xTSY~gt^PC<*Lbx{XrCZg?&HayanQJn z7ggA=!eUXwx4YK-jutIBw)E|%&16Dz`{KT7UviTm}h5;XZA6;L=DcGz7B-~jUk9_5@?>s(C zlzFIs5}Dg7u)Mk`rSkKEVaSffVzsH(z;t*i8^;%vX$WdHK(*}aZY2DDtft0fp%@4h zG244deVo}|iqxelSt82bL$u{BEF24Tz?w+<6* zPfb=BNuAy160DqUU2LxG*n{x*v~zzG=|)DDb7<1Uf{QUCu0}VSD1^MaV5REp=0xwLpnfbB*|8{wEc6x z_U^gHgqDlBus~{so8Rt|7G=5&h+RlkQF_V_DT{x)$$CON8Pw#4xHd6CUn(K_)=nxN?3>_=(Do?#6aUW$sA9Nc{H zOFa2}mD3h9nkN07+sL?ZTy+yO=@R-&E%@jm?G{H|Z=h-T97Xq~A1GCNiA|SSBKCC{ zZQCX95Zwb8Vpv3lFk8jN11IK>TcFt*HZw{-DE#(^gqu`Ry}=bbZfNfyGqYto^uTTq z3;HB*0zk`d)&tfVyUHQ<&lS3vP!4lxc12q~`Cr~Ck|@N|Ihlol6C5b}u|j3P(}076 zLLN8t20{?5tegS9RK2I`9I+R6OcyyvieO>l z$f&3YQ4$kVQ``5o!&?;C5Vz-5pgb|&X!j&bk_twq``!>PNhYVO3*Y85h5KON30w(C z@PIQghVNC-i(QMqMGrEUt8FtcL1Vvd(aDcRc5@#Q9{gG+hINU#12hz`292@$Pbo0S zX^|JVAQ32b-{O`R=&;eVSRWAtmunJMJ? z(I)x&ML@@wc~purzw_nGWE_UmO6z>{rB>j_q+foPH}7DA8kv)mA~*WiFC4!!*Ptgt zr&WW^`Wh_L5ur-fV{0I_kf4PHwKJm{**OxzvmKV?MS_ARGVzbNvwVM$l8OhHl}7+& znU1F^T*=Rp#zyzC-|3LwX+lyZjb!?j=8nfdVYn1d%Z|~kIAP^}Q_0z~)X*lR3Ta;l zkAvdHj8Uh?gT^+*CN6LZb2JOgvCNUO8zHq=_65+6iMm##v*QBqVaBzyg2sv}Ji|^* zu2jiYcM<`tHXAHFL%y(huI#u0%?aFl%gJPxjY$8s9@*1(ctYG`ealHWRsk~J)SMU( zQ8o;J{kY$ur7=~=y_HEvUbYQi5g9g}ou{{iIGKORunE&5?LH*+??4A3WFqlj5AEO)XZ{0mfP7LLr@gT%99pK{*x#e100J zqr{FRQGGb!?{pCqUB`6^yL&zSaJ?`=^lgiaTdX!nHmB2D-Keev06*z;R0Y+V<^C^~ zb1>kp*WdZ=v?R4j!l`9R%CX>ZQfmraNh1}pac^$@2!C8H+U6gR+b29dv`i<9KWuBA z*$4ZVt3X_KUG9{ZI+c|#_vQ)JR@0G&i@K%mNq(Q?K-9Bv3dPn^d{goYS_(5u?r{Kh!6$=-t1q6B7jSItMy zC_WL1905@5`X*}}Tvr=*fH+X&Xbjrsqb;zZ{YkU4A%M`ssWLtN)#QB;nccMQgIZ-k zm)pO+Na*A|qyeF7@ak-n|CnzeRW@EtLt!CsY9=R3q%}V#7L_9Y=~yis12vo^IIo^n zPMcGf?q{!|M|ow+6nB(JoWoKGa$qWk(7D|SgmBpsI*(&m40~?c+P6##-8pHJN{?zk z4%-ro*v2H=TU2XTMcj?&CiFS7(;&u?cLU;{-NCOnX$A|I9b@{o^bLQwJa0ynRn?e$ zz2gtepdQyXMpNl=6!`u;)wmol>1Vlpr$?o*@ZhcG!!f?I_LU{ptTSY_q7vlJrocI0 z#@ZJm{is<6a22=25wg(QbHfx_3K(!u9{S7s9}z>lJapz66n0IxVoDAzI%Hp0qAPI+hJet~mZ8gWrpx6zDViR)}EZrL6buM9ZHW=bp99pL9eZmDPmiUIC0&GMzuG%(f*OBQS zU_$eOG(UblkNjYIZJl6Y`7<{mA)$<&9W+vj3V58NLMn&b30ErE{)aHLWi;hv6d6G> z$R22EHpGZzZ-InhkFO-m$qw-3cmo)5##7OfOJ8Ab_X=ny}3IdLRl#PZ4! z$m`#wIcf08XIpjB<|20PNq7lln{fM%MISw;JM`d7Rbb^o`nJ0rxQan~&PAKESNkbK zUATKnq=+N=b{TdWf)<0WT1~_w>EhtO-?l!+EP5d!lT4&Dqm;b zZ3iPx{38a;5kbU}ED-8kg&YB*%4ueN6=-f$!`YHpx%n~#_M4j(_op&jep_+ekQ}_a zY%N)8V6?gB^wKhlbxIf|xg1{ni~Ff37#RTH4FW9w9-Ye!_U_c|>?LUf<5Qxast#?B z_CHA8f0d^bPD%iqW`uH+!t>*H>>s@2+LAvml#Nga zFIySaIENkgkfjDJjw~p%Qp8WAem2s-u#FV;T37F1t^OfQR69OcyGi1*99G1pEBRt6 zneRL+Wec=;@qok<4U;ll93m1FQ}=JPt8N587Dw5{Cnx~>kZ@!^A#9R{PMi?da6&UD zT&pwx5_E~;E2I^_1h6sae224IVy^yQMG>YKNv8{3&l9@jWcaR}s+6_~O!)bndatp} z4WrXNSl?38KfU9gl2K=9$Gjd@(FHkSPucT-t@- z+PN^of;6UIW&0&hEZ^7(XVMLI9mA-&xTGlL;gz(oSATR~MtUm%dn{(b29qo1H(5qd zf5FSbEl+}?W?jFCS6d9Talzi9pAUW^!&kEH>blVQlBZ`eYxM1Jhh3>XPZt10Yh-d#TnX*v@p1~7!TscRr2(N;|79>7Pu%u)UKqTw~hr=gD zrK=Y0z)JDAU4|D+hMQx;#~((00_DKMY%_@l_eGntwj4)K85fZ}mv8zTIL6fF%%|)JTZCK^Cl<{QIx3@h12!8oa4B}(Tthud@U68; zbk%cb3<&*gg6?AjX8!auZk;w-ePuiOZ#QL^tW1i5ix(v%iqZ)jNSRhJYl!NysOrCA zx34YWv9|tzh62SI6EJWVK|+t0qykK;Smh5tep$aN*}e0RE_1LPo%<0p`~*o^uR~gb zQK$**$&`L-Fyt~tXQu&u?Tnjd+g{LyGHmMe`+PL3s6^6nkuWYwaku^)D3~TOgBM6( z4a@OgJ?Jm7LNnc0B5>a7`V{*+#oqhZ7`eWxxS-(7KV`~D;^h&^IKvPY?!4?I_OQSb zR=He0GExT(ld$vr_sb6``BEvve0kSz!~6#ur>jl>=FCT2CDcsO$N~P@bu4l7sQ|tp zD_M#T%w%Sl%b5Xa_UtSNLXo;Ef~sj#!tm4#R$6uWvKcP4IP&V3OMpOs9u0?GX1zq0 zwWCKZ5Ty=;t{e`e@rh17ho5BGFz`6CeJgIWOG>AB@+Q_{hzS5g3j7#NMNIyD!!0g` z@b&ptT#7GdnakJ^GEl{o-~%C&fLMfqu}%)t06IC|VC|xt-_U?B7SJn9DPNi`D*P{t z+rn~Wr`dV-my?&{GXf2b?p|xxO%@g>ylIa`780+>erqw44|o~Wl`n2|cL{w>Ird3r zek06+z3_4~_DP0f#)^Rn`kFWMPV%lpTv^dto3URJa*drXRtIrJ`3XEV?OwQ5W!!~g z@h@4!ygX^*iYLFF2qO%}2cTL6o1fRe zWN0jQ!>=e%OwjMIA$4PC12OQV9W~F*kN#EQutEhJdU$s4<_6dx$7il~XK^k6`o7=0 z8v)Q?(~swP9NRkh^tuMvWl>K~@I*;)00_|C2D`l$nH^@$le(hvy-3-zuHGwk?Ho8g zsUmx80X03YeS1$7W9M*#$tDG z{=@#@@i^ltb36ifV|fsBr^43l%vTyL+pl`z;0gKhbQb~10VXhVJYewCR#W>ci=1eg zVUYpE7nD_GJ)q60GRZk`4*x2|)sO5qL7oloDI-`6@bUKzY0fF&L+LN)8oqz3u?`cd zNvK4n+UQkUTGQ?@}%EnOndRFyB(Vp?xJzNe#F^Cq7zY zSn4!x`{WUxCI~gqWXN4`&q>5q5}~1w<1+~c_oW&Q*;zXW7qmNGOE?Yd)$#PMuW!V6 z4zpdoc3$eqL18uNCs^l7)NdLOhEW=fiQ09`Y-m~qtS|6*36kn3VRvrN2lDbNgc>#E z*TtZzod77(RkDO>2c|cH=m_%rXt!~Nh3*J=F!iIOCU-eR5MUR9*vNER+=>$%1V10BRGPo=tgK@}8XWVxY;qMh^^ zDuy;NfTUPbRus)fO)9s-#?mGtWUBrCUf4RY#%Iqy_I&|WYH--eLoyTKB2KCqPi{jQ zPZqK?3Aml-Sq^G@ladtfC;GsJ9U1on6Dp&oJ{5(1l&Eq%Kkw)y1;oouLf&VK<}KA^ z%nh;US6YWxr2ShnBIz&@2 zIwV-ir>6~u*wCGvT!6DE6q3i()KZ6`XE25V;1#8bZcvtK(Zi2okE4*2>(5PMYC9|3 zKbvP+_F5D6cJYV8kZ!-4=UMr%rVjP)WFANUQ9k|;twcBFsCMt)_P@EgLmcCOwIKk; zjD5oi%paTIgnU1KhB?rPkIG)YWnHxzo-kjHLY4XXqAaYOyJ zYPT}`rS_?DFK;F|ny?H9#9SdXX;5gwfNDhI+RMF#G8maEQkWB++_Y%q5fV|et7#yB zl4q5Shv(228#8f=JG*JrS`7$(BpaJ(0w%H2&fi-(-LTyDTjvBziJ*ncLHojfI}=j zI;O(=ya(C7ana(A_UiP-BF5Eb9{;YP%12QwCK{I`)*47+7I@o6TJt>2R@Km8wO*j3 zp`p=iw819yxkCXw5ugB*h-)3c_j};kITs~Ck>}b+tLl8Q;w3rm^G$j7-o}M z5d~EL&e$yX4NoW&9+UQhI`ieWJ|&CO;6!h1gTGPzvoI@0LQd<;Jj>qyConm~Ws_qv z6b_bQusr;Dh5M&3QByM#Fekh4k@kMhVs`mTiNqa>fRC_tGx^@${NYUTTB^)!!Y03} zp|cnqUj-goOF!KqgO?~RA_LXnGP-qTf%iQ~aTDBCPH~m0UYJgwak1DmaJ4P)Z=2Oh zWZgO6aY%+Gq3J;e#Q-EZ1XCUsjdW3bQGx2@EBa{OJ^#8)r**JDuKn52ZrtI_tdaS6 zI+a~h#A>;W;Y}R{S6shI>DYm~g;mmLSOLqexN{~NybG5^`T;v-#Q7l!s|FhN$}rNf zeBqlvntk$KPyCnZF3CtRCvT^&3f)QE(Z<~pnmm&Y71k;|sG3`GwVw0Tn0B>FoquH8 z-@n-}x&$U$4&9sp%DSo=xf>^Wr;T1;`wQdKLrv1i?HL7}C;Zp#sv5i*9MhITyaJb3lhI?khRL)sBD?MP13i9l73Y5@ryRD5b#uqhdD!kCbs*lY*7o&0xf7Jon&LKbQ5j0m0xqCjGX5(29B26 zDF8j*iT7rPVM+#DM@YoNb$efpq0uBr43eAMQQB$0OL7U`Ad_e}acqTc}O zwb?bB!@Id4RrUWz(^rO7`Fvdq2uLg4h(U^gbRI%dQaYuS?(XjHZlt@rJEc1gAl)Gi z@9_ISFBkC1OYU>e%$~j1UVANywwvJRa_PS>SKRoa?tPYVSrH z$m;zstn*aq(|8=hzKf!c%=xw(M05nuA*Wo8d4O-LSEq>iU*yzNXK;~!<}vY`s~Tsab4s41CQ5Vq~2l_gDNg0(Iv-}@06%q)$2Ob| zdxb^y;K#0^w6jy-2)H+cpV0@!m1XTDE4~@%oHq&`b~Hg`u+?9|BD}zTG0+>dT6W{M zqpkA!AHDtY-Rp=WvdKI|KynV7q<+1gG4=Z3O;T3WUkkwQOdtzO?FgC)z5jKz%AWhg zAdIbWR9~Luk$cd}xSAS*HI5Hx3)8mczcuWzDZhWA;z{$;`$ZbcZ{0M^zVsLO&opDC zsQ77DR_r1YVJ!+f;x4|7EDhWs{Nf587^F2YiQO+Zwo3dIeo#D$Av%jZ8PgUmI%HbA zSSu;zZ{p#!{5@d(VQ}iNk8BEMDn4gtrCFk=XRc0079oPTn((Kp2Kb7KNVH%%^>S5< zn)kxf_pgt#*Cz-v>8OS(Th?@($9ohjBq#z_4}I>r=e0ifN21fhbI2rAEjuSt(>u?S z2;C)C7i1?ROA?&pxT*Utl81y}M9Gu>$|A2xwUtB2;xW4QY%t0-^ESQ9 zL~Eehqw-*TD4X@h{QHKBDD*AUTd(9tTQXWzwv%A{r||U9wvb&x3Yn-_|6HTQbR`dx z*%mBV(1V~ayY*Ndbq!h2!ZI&S9mB~UTOWP8551MaGE2r%kbT1^m*d;!_K5kUe#%Sl zvR#KdLe`(v8@qH0eLoE5#|5h*zu10Gw#Iv6d%z8&!vCsK9;mkUm`J}kb2dQq)YZ<% zNTeHD-;B=tsuX&Er7ycUFRCtm)>!A;mf}te7_wt@?*4sk4&F{Ri3D;|>*15XptW3e zaf_lK7*rSDj2z~VnC8=^Qgs*z&wW&0t_}-Vq~iYPYE)tW#}Ui&;V29d$ET zi~12VD?B1A*8H1bJDxb*=3wB`JT=&hxF6#!@kHcTy;31h?8tzUrb)h68jYruLbK3i zDEliIOP&thAI+mY=jk6z_t=?}m&OW(-=%glpf&ouO)AupGbMNv(2flYcnu5#=P$1} zs*~#v@|m2*2gU%YY5ioq`J59>nZj<3UNXA7;Zmknr!Paq&!Bip?P%^EfQpyxccfs^ z8Ld&z&jT_|`7xSz5%G;remSZZBeAoVk3D0}?ocD-P(JgMnF`AY;i z7G8X@9-fyVu^DEC`kS>+nsP*r<1jxijdx-WqZFAiZq=ykpFwTe^;f|A+BC3 z$Yt1Z#DMDCM>h8N-y&$HS;#0SY?U?<)^8=nnd!fH1~LEp+DX2CKcBB-%5qDS&Fo@~+?VE+2y>y0V+hA4fn``{rQ20g$3PwwVZ6 zXnI*@t1}EihlGn(sc~RTI@|EiN-4RIS1!`KHypjd0W;}*%zXP%1k#x~pUAM5uenm_ z`js7lz6Fu&vsb$MtL&l@Uf5?oR2ly(hvSw{t#`{E0N%i&OegN#W#+hALI<-w6{X9P z6>Q;K21Jn;W-m*n5byVBu6031b(kJSTjbL7SS$W@n)lO5f$_5Y|BG>y#P^?_xQa6O- zWG%L5=rymg9xhBE7~R1D@M%l-;gI0oSvfqDuL?Ng5AaQzTDByB!w>l3x*`Xsb}ARV zL9imE1p2$**=lM=&4M98%?+p}f8_ghzSKc#7oEd1QK zEFknHCAGi)BB~+#`a9famA(&>_SX4Dlt+AcHwVtXi<=oHsBos%*KF0-9 z8J(QmG{(^ek;3Ey%uu9`u}Kk9`}Fe`ws?o$tA`sczxxEUyy?*Q5TcK4FL~K=XH6w7 zKD`o*!>GC$YSj10r2eWcrZW>?r52-;o*Bdwr+d^e#Z#K-yt1N85L)(4FKT%C{ta22 z%V2NP_dQJ6^~9Hf63CLW6~?S4g=mtpC94F;rxH5QQT zo0O$JYeJ<35C6|a(3wF3ZkZXhF&eL}3F2nsV}I_~pIxp-9gl3SLnm)Wa%ib9{0Hzk zjf-l}{zSQ-g^#UhPsl0hD6vck`(+G`slZ8ZE@Y4Wg%oX{?VQCYK8EinEA3Y_CHygE zCp%UbG|cfjMosUi(H(9Ful6@}hm;0_&gNIDKBiQ*q)L zZP7MNMlyn*<63l%QLDIYy1Kw;i0uH?Pqf7fY8usI#J~hNI%Q$6n|hPdUK!tU{6YrC zLbTyMK`xl_(s}%(S^xBqwg5v{%GWkGFZRtv#HGQ_7S?+_-kQ+l8|d>|04Q+CYzNWO z-1N{lo*Xs7gmD%^|0oJg$g`h2IN0*u+mol*V7oYrlwS)4Ry!(_HMu=9sU3K*76BU@7u5TmFvd25qGZ zV#%y{i)vh}tl;Ntzr1fquH+HH)joK3nRB67ENw&M2V*?jczs!h0tAcS@}}GJGNdYk zAPwjW(TPmP?2p$@2pCdpr}+2?V6;TDtU|=K#CBTkrrLyO{^*5n5Q6PevJtHxOfbZo z@`pDg95jVm5rzdk(p?S}2>F@P=`V{E8|v@R#J5H@zJ2;dQhmm;gnezTtkN20@TK(_ z9_Mf81H{w#$m{oy_U7<*v%0NH&I3ih9Fa`hWwSbDO{Ww^i>_rG*Sc?YlQbDB*nXuq zij?7>p2)fW5wYoXU*N;!VYE#;i_VavV|E3nGT>CSzVRI_Y#AUf~1+wF%QTBR2lKa#Ar((rLLS=aW_ z;M&jbk^Os$laY^{bZGTGd|-@%@4~k4Co&S(TBztE0eA11eqn`zzbwDCt{;j7%{7_>I#A z9n62wNLnn{o6PWca?Ladoz88Za<|!9dQDKVm`S(-@}fUn%5Uu3tNl9vTl$w(nx?P( zb8=k#;x*G3k3h1?ozN(W%p4n&arS?OPE*xpp`tL7)8G?gbMAU1`;3W6R^#TusN}-w zfAUpK=L^nbknf*kL6wB>;u}Z%V;d9VnKUjdM^LSY0PNYmsX%Jw5$Jwre`K1&G+aWX zmWRV+jdhyl|2{6mI4%L#MD)dt>rGR1i6#BV>wrcyf#vnhO-`9q^a)nq5J~b4TW!6Y zeuIdak}!hT{0e)rF(p9O#8Af!)_St^t)z8%F15s@4N(=xk~Z^?Rh;r0tLxmG*5yui z;f=%GeHX(UXFA=w)2R>dm~*gfP&VIK!Bd_2R}>H?6|&g>WUzDQNtjD=vv(pClKn&2 zWM~i+RAO0~RpUY{Bfo~iWc?=)b!dMmDvG7K+KF}C278j3diCh{TtYudG)2YoeTbu4 zTveeCmf?F{-}k7-m_~Al5oMf9KUsNoW=*hfJ0%X8(s(mVxgSqy!P!liv4_pOOg4}# zd`X-%7}314CPVdZ?)m6k=^D zI&R#L0*{p!@P+HPOAfTj3$iL}`vF!WcfSJ&3jfMQU%;1>6&U zFScn3+5+6cxpv@>__xDi&BH9UI&3A)`G3(@Z1V9IW1V>_t-5GL#^NVjE$UqV)Xh>X z-oR`trR?OFdh0)-Kw4Ifyxq=!S{%i=+CN~C^lmWL|BWL_vGj`Qr*NNEtmcUTDT(;WlS7l=!Jt1~STZ|hr&>5nZX424xO1ld8ZhYyJi@~PvTH*fr32Nw?^Wckvs*P6kI&DV$!YJQh6neI&eUJ+ zQ{OL4-(>%UhSNm?&TZEd4m7-xs`(_XCT&0$;B{!dy zmTpxda0nU0QIZF9>z5)2-BH{kq_ZJOLJvVSM;aHzM8>tcItr6@UWkcXG9nB85#uF8 z)sf^S`o(WObbPVDJ0-=WQRwcBz@XQhW(YEqh?u9auY6UImlxufV+OxW5AHKqrBsz< zWs;8I43aFQHolr+eIba|`~ERjUhKEL#H8vEGcyE9NnQNh>G@337$;wk$zU@==A88z z&sdKjOsz7cvnI3Sq@6HW8X77oZ1twJ#i^1kP2GKA%A~~)ZG4opS_;8Ns#0=z==;ez zKpZ4+&L!q|bWW(mhW_siBH0Psn*5*%Vy|+|)hW84vkpm+;AQkT1x?FlNhd4J!Z`3k z3Q6(f7n+8xQX7}c6c=nQ?shHl8vEuhdUdO4gK7JA26hPB|8yMqAs`Jp<=|##=CV`h zVyF;+39{`9x_!}1jQk4{YS8T76U4z%>C++q!QtMq>D+~r1KdB4 z%VH3|Wx9y7pHj)G$rPFblJC5-s2mQ>h!;wwywOKS!+SM`!$|DD8+spfs;aXh63rlR z^xWv4IrZ+6R<|<3b@J3dbRV;|{iDxY{>qHgXK1}v$&u9e2*55(F;?cMyYGZgrUjvG z*}ZOD&M$3PyF-<4xZl*CkCM~|K8;APEqYq=rk_-JZGcrQGe=3UZ5*5{7`yHpPNWC}bVqD(4 zmwi1r|8$3ynl@>eLA3?L<-X}8@Zpl#7QG9Z;iH_4Dood%XVz=vUC^WnT{go+KYmIP zdl#LPm5CrJ+uC^Eckr=18+nv{W$y(QXGx~u#)oL+#oBqXJe-4naK~6%P6AX^Q+Ybw zOkyV0kLvOFIQuWGw{H{K#`;wBr@!cl-nVlZ4)l(akwdOAyiY_Z#B8|*;%Ge;>nkA8@(3sxJTC~ z#w=K*DC#J77D16goJ3OAl~jN9$7D`ne`2pcW9^U0fBGJX|9acK3iEeDHMqQ_$VmNB zB**{A*KizUp8fsfzd$T*kfhfta-CtgRbOzjWIYeCjMwi=v~uM8^XpR)f?%(B8{yp< zLg(j%vUY1U{fWAmK{~~JWj#mtr(9n->r~+mnIogzu_}6fo!O3PYR1T=aY9gA+b^q= znKxbGRBQIbwMHuLi-@KCKO!VK*c*NXu`#tG9cSuzL#m2OgTr zna5tK%C`lMWX9UQWtGSL{5K=j9e%WJo8)x=)vxTs_irt!lvm}rNQJc5*`t33N8N9b zaSW#t0eLfa*V_-kH`+5=s*sX+R4eI+Iqduqf0(N*wy%l3McG|ZA#)u46)=sA?+I>^ zNK+rHncbs8=00^u0CmFVb{?n(M!~(_8*biyysDrwoV(C(b#tX!nrq~<RC{cym3OHuJ&=_N==a`0Ilb`Am6+E9$9 zi1i|<5Ycg8|I>4|<+If-Q0O^NWXlwJv*d;&K|@1?L~8~9gNz(-52XM zv5T?Ym0ItES5F$R+#m5Sju4bm(KOCEoxTdZ8aH%kL0E45XxW6OSZWh3O7)UZdbTh~ zJd8{9&#tbT20?)YVbex`vLZ1PVHa6zDdr=4CyVW)=m&Wl*VR1SBmwD230R)C7bDxA zwrU;aqar?C1f}&^m>>?gA4>}f(oyq-uI|3yxeZbQbM<%!geh*s>>rvJ5^ayu*4KlJ z5*RXJy4X+7VYt!pVDjQaGUc$!C}(4*_bmH=RG^nTRK(vMkLk{pvwI`fy}h@@w|!)g zj5gqua-|XOKU~c&EC+$@c2lPD|8oJz(OdZVw(B>tb{adyD5semEQlw4Wb#uf3Tx!JySN=<-=B>xSP=ZOM2RQq5tbDJaB0Y0K5LbQ073 z#4mSi!J710X^}HX5;Npau%EGm?#MENYKKwhYs$LLenmxgV@4rGFrIVZSLQGXZ_vcj0<8DMqvb9Q{(YnA- zPVBu2LP2A5{QZEe;Ce_@dZy}Zh( z>;#dom7XYld89XKBG*ZF{nfPmOB(zsj=wRY!4!l?-vnt!qbA1krF-jd^UaT^#~UZ- z6%il}WKo9K9UL>3IN<-M%cWv)wBo5-Y4pwxGkS}?VC}|V%f(kq*+0{mnsdRdsp?kT zSQW6#s3RN#`vaXd@ss6O>xN>l;#{PG9Iw9f>C8hD`xgqbhN3-z{;tvWVoH;rx ziy3mS4X;&0_mYaPX7cy9#`peq{d4j}AUWc6!uP0&zFu*5+uLK7#}OAl06GWyr#kd~ zWIx6PF-+fMPc)ne7{7C&(lfo_BHki3U7Ibjw%Shh1^R^0oaj9;KP(_Co3zq`b#ahr zv=XV_Jl6#_SFO2ygcNP}22GJtlYxN@@QXABc{WBn@R`ZnM+OizXbxhqun;C80O-Yo zlNpUWtu{G^egPy}z-uPxvxZRuV|LhrYHT>~S(af$y#9mp<0cl{7;iEV8}kL=P7>Gg zr{(M+VYQoe6g;-&DPM3h!0E2Hlm&stt3dAk#eTd=8miOfG>*ER%Ey`-LSPEGHZEd) zGv;0io`?X_>gnY*6D~Omja90wKdgPHSYidd14+VpY7;G#<8RWz>swFIo4pW7b3{vkEPMl2$L4aY?b43qCD<9mqz7fRH&lJiOsin>#IKs{HDB7bbX0P}FE$ zZQPyK2Q4lSy7ql`WUzWM>_*6H;+^Trw`g6d+{#7-lCj>TsF{*)#Q)M9-uX-Oo}Lu_ zIDE@iXDhVII&GHs;k(rFLFvWl(Sq>%gSQ3DOJ@wl^QhYr6^#W8dK0Cu1&E7RTB3o{ z90%)Snl?9-MpT$A-#?5mR{ZKMWmZ{a}4?#^m zGhpHM_xG5by(xlwelMv@N7I*hfVt=DL}u3NNU8KgWBkk%&62NC%G!bLb$Q`SpzP6O zGN+}WtcYz42f-eUh|Xs7X9ZI+d~a*U{^H{00gj1L>vd-j3cb(uHbgKXx5m|Wkh-S% z-vWX>&U5w(#wxzOtJu#8FHE{POzt+Ta~liv=>(-^^Z->p&E}?F{XwO;S$$@RX3IYw z1k3C4Majxa8}JQG!In2F0Kk}EHhcYWjN))m!C-4k2$X23eSLSmlQ0aEz!8dxomZ~z z??WVWP-&bRx@uJ#_!uug4vt8xE7rwv`Whuwm3C#(Pkw@55 zsgq2EQ^+&@srkTTY*Idy*xo~#lb^Zoo7*3KUx>~ADv*j!1&N*iMp*C{N2>?7E;8Fd zC)CLgizIXBFkK!`pQ{O9q}T^xH*pHcD;hPQ2n2x8J()Mll1^5>)z+@Wf=6@mx4h7b ziRDx@IfVZ)$o7Rsom&T;5xh~->p)e=Jj@9R0yJD1%?%uaD&4+!&zB>QDc}=BJr>RB zKVXhuKVH%H4-E8wh*2yongsdDkjG(c_WE)ac{Zf!q{3SAr(+NcdvU==C z^*j8Mz4n}vpBwX&bi+f>o>SF|PDzE>)XRMmo82h0$K_NfBNBM{-7WNYc1>dOpQ%BS zxpAq=m6ls@GN-GSUp%$5$Tk2Hjk9y6%3}wgR|sgOZLKMQO9Eyj?KNG-_nt?{7k5`7 zo>|J2B++8n6zAx0f67qS@~dTKpXKDvR{UE@G(@wkgXbzH zqY!acYGs>={c0&`YcVpQcg$V0yE_mq#X-j>h1j(W`3pFV3pJm&hED;sjh8nGF4X{G zg`>uz7?4LZ{hDI5)QNF>h{C)F8_801-h{ze5v@ue@p}0fnd9z&5E(^{%!fUL+;uH( zXiem*GyK@!9jD!cl#UbTq{Nf*tjeBj{h=hiyw-^Jq3iCI(t(Irptt=B5`)gy5TI&W zf*wJX+W{IkRz3UnQB!i*PF+hpe>wgBUd`VPG{SJvtd-Gs9;bWVo76i|++V}Kx>aLA zAFr@GCP~`H2@tG)uWn~E`fn~JC>1iKnu4K`BF6XgwnM^hb;W6b@$byFtWFgT| zfFfHf2{|mzXB-W#R>`Z&>;cBY<{->PcuZzR2GkrK#}}m6@XzndfQ?CiX3d6h$;tQ) z25*9hN@A$Fdy^l?Bz*)LeO{nPX}1?Dd`@%Y^l!WW7~kBC`Z=EeUFO#E{N@gTX#TOQB-f1bSFnl7AQy^*>jlH0otH^-9SP&)c9oWWjLhO7ieTg0EJnA z-DcaH7r_nNw=JehLu|3o_3=5GJ7TEcgz+|dx;c#>T&@*~2XaQdnbe|Zs z_;kX>jB8ovzNxn?45*pII|8i|DV~}zbJwCca=~?Myu1@9G*m(D@poji8ndCGLfG6^ z!_oUf&_6QrTqS^%2>ctW&t?w}&tV~s9q2dKpBU8YHQbQ*s1Ff9;PUfwMMOIO6hny}fo zU03>@zLV{r{foJpIy;%SQXXc^V5=Cq) zA5#1&l`?Hkf<1*C(nbQS^WOnjFULaOeMWODe`-Es`#?@Fb{pBr-j|;T+9eG=M{_>J z@Kbm5`V2wh5i@kd*+4(w9^rB(N$IU)h;C!hcqUwiAKY5H!^Zx0iwIy<;Q zsz>obfvMbvL+V0W8{b72-^JL)!xFsm|oPq{eu8NXFex;XAJol+B_O% zSJ*`Def9YiPnO>0{jOyy%mJ9i>UAMd;%O=i@pmYZ^-W`gDmTt89Bi47Dze@YHJAsc6Kj zz-4wmb}VLC;0@R(g+(-14w9J=iQYd2V%48_mcNeX)G&3u@bBtAp0(suv#9*WmXWix zcO6Lr>T8S&P+F6g^lqQLwh+C3h8ftGK(Fs*c;8x@^V#zb+Zsl)SanrPZ~I{F-GB=v39>3UV#YQwFmFF3dOGr(3T#%d)yLYHs}&T$eyw)= zzLz6*30kvRxxyP&W9rR!rRiYDg76O?ul`+9F>dr?*A{@m&mh}GmHwUwB6Vx&c=iUM zjZ!~7+T#KU&hbj4DC-&=1;F7asb8iT&lh)dOPZ7_+Stj?_7I@?9T6R^{U_s^oFE>= z@d}7t(?HE^91t3V0W0gzG*v&n`pfZBcJ)`! zXbpGGI@*@0iWKNj<&b7K*lg}%Uw7WQntsYX8>Ch75g-7-(p%d7wK|CI?#p0t-k-7q z`T%M9sV|6QTv%&y)6diZpk}OVt5-b?TDsKD3`A+JD0cFl9CB+5*4h{C-kNRf+yyjX zbe(7QW>oR0r7j`a{768^H}o5Q$sV&O(xi`MatimoMS_0%2y~dqn1GWxY)t=)!%3vl zgUoY2D?pq=z+`lDo^I{9`};NI!BAzNbJ=m3;n&+{?%4$;&c6vfq%-oNrH|aig{gq8 z@ZsL_<+!ac2Jgw)oNhzCIzrp+bXW_`OLvmrkyflzF$@e#(dBGK)>7sr`JN)0UhwJd zDwG{Ulf_45;6$M#B^NRl+!?GamnU#-K{_b8W-%?C2+~&Lk$SpzarS})_nVjd)^}ej zoT^$a@pIcHdOS&jJ70Uni53i5j6e85W^On^9Ya*GiJZtp(1nJ(d~dGJKw%@T=V31I}J{q zGZEHR{wOwEY6uI1#09WOc5X0RyS89F)bKa%GvIA{1Y%_$R-q-tqt&@#lr|APJ`!U4 zLDwgXy%_EoKef?crJd<&YA~gPWmi_K@rAh7C(+ZeTK>z3-g)z>+vFYt3w83X?hX}I zcNY4LFd-GMc*mqQV)}uE>KL=6Ns^yn&BmVtgS+b&pr6dZyn3KA(+e&Hr)?G}QTUf43k2R6I z>Y{57jb`800?B5*cfIK->uq;8w73Ap_FctsD6N755~u5jFNW*8IXI6N9NK?5UjT{Q zR7KUPoA*&h&v}j=hP%lMOc9%)CVB|z)ZWzxbTZ!b(Lb4%5?HvOPO=Lb^uxkWH?qNA z0>}ukpzV`F}e-tGz$cQaH>+`=gph9jE&>kMrT0J{{V1BwCw$#LB7;BTkMd9Ru;mr+%h z!Y+ZjMu}d09^7#0>ET5cfhriz*y=4kYwJu<;s-zN_XIok)jsJkl`0 zn=iQ)g^lNx`!%E=Np(7d_^vG9&L*B574<5IQ?oC3;c)4)L$0}c&%L?rGMXo-E+IE? z-T_IAkY*8)Yh3>NrV@M4s_MqEFe|Ho2K+k67S7iuJP1+Lo@91|+^F{2lLTp0Vc9tC z#xC2=Vlfdo*jFf2Sl<}shpQa#pD}5Fg`9}~u6Z9jS-|A#ga#A~mh9Bt2nkUiq-OAG zz00(i)qv-Ia$yCa>R+X{h0%aFr(0pp|D_oMfN%~{$8wv3cqPpNBiHL}dnJ697rcuv z%0|79hvzn+vc7O93mVN;mW;WES^Y?m~8$j-W?DA2GJFoS8e67_`*SogzbjK>zfj>dP#347 zZ;9#gLAvBV>sLfZ2D+mQjFP?}ZF6qU{euU3em)R%`$m}GIEt}tU76?p zX1)*?bd1MQWpX}n)mpyw6fXuU(rasS?99YuMkR%;7BAVi}}RaQ#zO_v0Ap#%VGOw42k^to6TMnk?H8_;N0~tP4$$J z#gevt!Ua=O!7|@YLLw>=`-qePb&^k^T7z=+e{$SXQT-prLtUkLcOw=0L;KXbsa?Z5 zOrO37yifDFA?ry0;enwfAjyNei{{=8BSor@(-b-5B*I+;Cki(PX+z4J*44M2QnGLn~QE&OjM>d=FF{T%Ag3#uXG2TSQD zv|LG#_^tLInm)mK#})0`HxDNq&Bdil!=rvQ$gUGS6;%tZ%cDyTZrr5aASwC{sB$gN zc{0O!hX?@9fN+@;iYmqhAq2p`;?~4 z%klGvPK~FR1Yd-Il~qtvg(izAHe}^86x%+P-X)n;En0u^8`U~~J-UBMch)k0cp?@Q zwq=)0HR#z%M&p(j4_KbulXEv+ht;(rUpTWx`jjiyQ3S|I;*Fokm;W!DAnGF9MRjQ; z6(7_ZWG~7NV9&bPjovJ-G6Jz~1Bi*GYx7i4;I6@2J@HR2Asm*rR$s?Dt(tm z2?^zae^NNxD(cykT=MQDWy2F5K0-{KirBvctvggJ2+f8qfc$y=iB`>G;rV>seIV-zVwbr-^~ zStpB>(3IpgGW$-$J}5#xVo z22L81;w}cewMosEQXe(s#W3pXAi8-zCr>`t!Zb94C&%vQCQa~Z+~`(STD#jbty6z^ zM=)-P&4h6;^i8L6am_S3=Dnqinl6I`N0~E0+h*B*`}~if;|ENd7N?K+-0V`Ttzyh2 zhp?yP@*$Enzp-z-d|Fge^S*^3nb7#kmHIYPsk5Q9I^RY*c76xkqrlw2Q@6Z2j@J{K z5|bvVUOB~Y#pE*d>V~S#e5JoT1?f>pzKebrDaK-NIcLiySxVWhWr{77ram=#_9Q$` z0{}an3Rm-Q20=!E)_7kU5s#Mnws-}VNc`mDcyz5J5VwT>e?Wvf?|#^X745xj1e~C= zcS(sPjbSD|h@+~K$m@teKnf%E!-95mxV9|4E>%+l-fSexXx91g?kjDW9{y~kk z4*ra8K}_d*4{2eMsYD9?N9+l%zl;hRN&$WLhvj*b$d{Ld01E>>-5xNz{GHnO8A}Af zgf~LZ&HfK-$D;<5T#3Mg*jC*CqQj~L=&yjL$ELYE3fTDf*L{Bvv0m32T8wZgMy$7P zuN4zP!-}9yOmEqy_5v}$Uk+un+W<)w_rnFnui^YVCzLO!1_6SmQ=E~E<{ZrrU z_JH_!{a(gCbw5Fw+sobc@iR)T+b3waR5!Es2q7gXf0S07>G`y^lXSxZfz4kPY4+TR7S0p#S;IfuyiXiq!X0M8=i<~fc#4{%AQ?Y z0ccaDY{6eCguZr?rG}TPL0HvLiV|XDytM`5FkDDh4WHRFF6edDZ*ah?341HqCq+wR z!hOQWd%ktUzF({g7Un%ArFRyerlwyS&tm3;CCbk)$RN9(YnZNaOeqnN--hV*BU4kgx1|uVC}*tqOSn{1mhk>t z4v|^_je^R&XE4?b*t^6791}#%S-aFP|N6|l_s6^~aF@=RLBICe07u;sH-z}byl2_+ zcVnmkJxJhz-9iVrpVxepgzE%I$JuixBL?}H5f%rv2J{)O-Yd5vq}Wj*cXhvE$YGNp z!RSMUYr8TIl_PEd>8Z=HbF8|P;YaXU9j>9=0JH^kC=JJh3OZDR3AZ~vfbY_l>78yv zwymZWaMT^NS?rpqpO+KFrSW$F>4n4CgxV23gPEGgt(3ks{l1fHt?um)xqh<$p9`Rd z0u{mItMl6Or?4Xm%cA;3^APft!gpxP;O~x*bAEpL=}A`uh`su^7o27dKM_F(9Ao}= zPY%tbnC_<@zkB7fr(kUwYc`Rh!a*{rheGmN3bn3#@)1u;wv@4Dm20joCBl7V}CM{q}Vglv}8nJtawyFT889qBkY%{g^z64 zboq@pW90Xml`@?#x_6x1e$ls+XO6iQrxVrlni}YKWQ-0cvV6cqe!5l4XT;A0#K-5} zhy6-JOSbabfAYyp92^%0i>$a7vyh*wq; z(oQB(bYm*!zmM~1q?(!%{8?h_m6bExNcxTM6Vl)5@`~=glkqmL;UrkW+xC-IhUzhG z>rZmTE6iv>Rb@c%6Z~_Q2<>H*R?|*VXr;WLZfY< zovcz`g=>@dMtB*}`mY5%n@p6Z%aec*;4UAc_ zZJFmiTfML|&L|unc6h}Rl(lYKFN+iFz{#&Vwsx>eA`fr<7oqmjk^u-AP|NLIHKq93 zq=aN{R5Vo>+vOM6Hu`V+YFU`?--llJ$|&s2GYxpaAOY1}K*=*kb*J*-QHl9Fm@f^O z0$o!dv*de>2I{smXz0vY9R7gT)$t2`-Rlj8@=PZp%_biRc$R?okz@K6|K@8zMzZaV z(F{z}Oih%~eSMoK>USG!Di&m|8*u5)&VqknpWbYn0Vr$@AXJu3p<7y};iS)mWgpRQ znt=m5B0$6f%^b0}8EmWefX@Qt8)EzraN>vFay7-$&Hq>PcfaX_G9>c0gb4*VbDv9~ z1K0VXRC_b?Ra2<0h(P!|2UA{vo&kiTnH$duN2L#SITVUfHnc~4aPHA|nzvg!3m+t~ zYh*D>4Rta1vkpN!(Sw`%s-^!?eo7S@4us{mPwQtwXC}I2QinO1& zF_cqY(D_CDfF)ZuMtX@_+Ekh%`W5hKUWXPoU+V;Tc`*YrWBBrl*E?}UYEmVKolNz| z+gWwcu64VeOa&eXbW-|@WzY9E0OK0KAc}67p%y@L_GcOva)XyIw>yf?p@$gIlz|az zAwWmP!$|MdIEM7N&kX-mpCzZN#IT#&2i(vx_g1Xrk(?iGo8-%;qxhW3Mu2BL(UTrL z3+1(;H7*H3CoA^gBCX?0b#wl*HR%P|i#<0T^ze%6* zz+#o@i$iAvjPLHT6W_UJH5Wrc_Z7r?9ALZ4uc?VJnd2xR!;sHpYm_52go0q}#gF9r z-&+mX^TGC#*5?Sbu+8{vFo4~br* z?6q>wuGaktGxO%D7rquH1N4K~#72Ji5Q^df+`tda-5oC~U0$CE@P{c_)~fNM?!dG( z3bgCejpeE=3s>IHoKMH$^}f;h0a9^`xxHIp%@YoJWK91mpbcyU^-~qPrV1`iYmeh3 zXr7x#(mXi1}@$Wyro&Yg%)3P2YhXI5gz+#+YI@w`1{I+OuW6%~{ zgGEFF*~ek*sZ9`vB#gQeJ++*WbuE5cB?@#fXXt9PAD5*+HU(28RTuk}qNjO;EOKKs z>)YGo4CMLRrulDc+ZY{jBqyl^7R#TgJ|FDJK3_cRuTEE-VceeXU`ILfl8nnr=C;pG zlF-V!BtNCT{hgOt{{ogbzp!UXGjL=EuF3Uj-v}(@-!pHs_Cm>WQ_2($q@eS~f1!a= z-5EL|MMXr(*Y+I6 zZ-vuK8BDXLGvCM7!V+Ji$!H)>zsX-XtlV`n^^q6X)=*&mSo>B^|JU2apSFktDE#SW ziuP~P5t(sJSj*WS*$-!a%g5jx0vrs%?Yip=h+iIfKTuD>)Ek(B0<_CRy|Ya){}R|E zzv9LvDkbITd`t(O)6Hflo;dx#_2o_;(d!Pt4}v9P<18qde&ws`xYDWZPnH75;rxg)!S~wc6*tg6c16Es}K2ToZ3;x;tDRBDA1znn``TaQVvu)705D)llJ(JSr zVA=n1#MkOZQQ z@2ZBgAlRH(k_nKwIzc{oI_Bz-F+E;ksD|zV93|kotiHRI<}40!i9&D9+<6B#DcQH!6OKTcbZTl2fcY!E+5gLWR{=GW z)Af#Gu6Bf9C9&lais4b=t$i<}T#p&&1|t`Sz$c4cO6-dJv|Jt`!s`?$64w%dbZ@wa zrfz@X=x?9rZyq3-Obl2mWT5;9JY5nVr)uewE(TPy$JH({u+YkK^3ut-v3AHwZJ1eG zA7|-=@_L&~k#hWp2Fz@lvF(@tk`MzyvpQQ$O48M*e-#>&#iL}2AE>h{_>Oj9sK{LW zjL#`dSkdtx4Mcm!(NZI5Ukotc+h;167(2AFI?`uZ@69vy6sxd+D;&_!Um}CH_!q-H zIn2i$hG!+4KXNLHwL!Bpqxw_XcsdC)WT@#~T@BuO7U!1n;~=joVmQbs^hw}zgYjG%S*+DHf#%k6y)b{f;ShnPLj-zvI>`mXN%V7q#w}4!EuqS zGustpw)$_2oJy`=?T3&o@&WdRL3OB<=H^SNmmKsK(&-#r!XT;(;}Pu?`t$K)_-SwB z)eT7Ac;{-p;uS}rN!gTAp%Z=6){?Hj5@E1)5eb)i zKAa-?8qn|u^AMF(h&m7mnsC}UU6+NEVKTI$nVGE8k18&HNQVo`T?bQhpYq7!%KW0N z*xi^fXw9Op-f@;4yXY&C({{-xak&HTY>8&A4@8xG6a8dpqfO-azziUJUj=DAJv;v0 zB0paCI0JBQYoTI$z2ewtIa)N|WaZ#(s^ZQpz2{^@y1epFy6*KgTS2=Fl9lntlENh) z!74dos-2z8|AGh{4miYXp8rjRR}~&VhPRE@*xL!}H(%qd~K|s2sW2=-%cWfGA(<$BEotu2u)^ncc8Q=H*1Me8W zHO2uC;=b2f_nd3ZxaKwQ5pN7vgK}_C5I$Yzo|6}}F*2=TlUI?ZQe-|gq*BWM_O9($ zJTi|R%wj|t0(oioZTLA__YF@7UAU-zo6yY83L{szgT2?xOfM6G@FP^w2bW10Os}~K zkDB}eDGz8d9hH#q%Y4e|td=eCQzMlPCZOkkUUxAd@9g{u{Ms*l?9A-^UV1PFYS%aN zYLLd*nib;!8{MG@)u`C0-`m0hbfQ{VPm=ITXv%OSOyJG zy(jZtWn-?oIKcjWUh32aq|z8CQx)j-^;;`3J2^s>i!Bd#cH6QB)m7lJ)Gkaysd&p) zI$aSy;#w}NNJ9^9VbAFu)`U;^L%U!ym>h7S2Dcx$1f&`cXTaIK+k!T6wX1p}FRfS|rh^ zw-aFz>7{Fs7SkfDmA+Z^E9#bp!MB1Wc~9Nj&{Ab1YoQ8S?^|e@W>LJ+UFz45M{2w{ z2suufb>P8!Mhp}hePkbgKB01%R)6YM8{@GvC26+C?mVtpLXk_l8i{edeXYWltsOjN zp2jONM@UQ@Nmm^b!dQR$0v|y$@(XMUlbk8~`=wXRijb7<*+xAD(IT@rT)Xl8VNGw) zvhR!QWD^$I@4l>FQUIrUqi&|UD*+ZOS*>kn=c8#o*0dCNvIrtff~T|heQ^Td@Lc{E zY1jp|r0>^%({EQAkbvw|f!|JXFBe`N0bA{r`v*W?gadxq`GRanuL63$GRBMQD+)Z} z4NO$rM@!lhb6Zs`}TuIQqkCLA_p?W~|$rPH$3hsXKC^YH3M8$UBZLd1`${T4lH9tM4lEmi{@4|A$GXM z$--waN_`Or?^eRKaRfF=S#$!Ds+AT5=E8Mah<5dD%o#;gF!C?7!-yxRkqm@nHD}h< z!84V5H1;&bP}dV}h^qFxroOaty~pK5ApwDm&XF{u7*nuEqv7O0fD5@Y4Ii!GL&7FZ zARY2MV!t9T>Ly*fhVa-|B^dSf4va;Pj`;7uCl2+tNDI}zx{lO~R(C`tICM>|vJ!yQqXwXVK=S2;M?=|K8~}Xn#{gtRO-W@n>3KlfBb*cV z^QZd_bR7S0Z);GibA;p!Ek;Oa0A>zsl&kJCy*CJV0a{9O%+JTi4=|qrGqCg;(emc! zZjoN0&3bQ?4UE8>*5|^_N*Vruh;FhL*h9XNOv6^rBHb^58UYMRh(&((a^*rIIp=+! z=5H`4F&JyEY-}px=UwvLx6-5oc9Fuf$i4+1211`WljcF2hW3Ew)sG_7&XNWF7e|9@ zq6bS!T3)+Vqpapfqhoh&fvkQf=%1k=lmTGlm;f@`R;c$tDx4rPI(qYqTaKnh)j~6K zo8wuf-i05vig=LZlV=j?Sn!sfJ|FQE?j37B9KC+?_Dh|w z#b?Kga51k&ls>1^fI}yQZl-CrF;bh>q+%ST5iLWcKR>MCSS_D;uY}d;B%hl&{j~9M z%i(Ij^QZ`Uc!b=;wUXjn{38uT0Z;2wY21X0!#Bow{3lZ8ht`m`-(X6t&jo3%M&fTn z9dA@jwNv%S_yzP>&1Ft=hwmYd1u?)mk zpHX}94H8$}^?jRN8cgu`4TH2l0LypFrD*)}I$7efhz$qrJGjl>@Q^T-Mnx8FKwPP? zwVZ}jm=rAM4hN}rk$2v{b9%jpI#TI99x*V0F2?+OtyCynPVi&p#MOxkFX)dgy!P}) zKr-zLIzt7}48MYjzjhjo_L@$Y>7I0+AZ4#g4*@xA&|$d*06@I=qlJ6KDhQJB&rZT4 z;#4~U=7Yyn3A4W5fmAmTB~fUWQ|1dC(DsMqrMn1-b?eH;*Og}UB~Byi$vw;qf2K(*<8zbjGk9G#x^v(Up{ww?H@lh>KI<_gitT}2-^>G_iBc6~1!dj8_YmyV9M zkw&`$fuoevNO=;_=XbA-p{gr+4V0rO7#sVP^q7DBPXFq~ixqK)nWKK?T&u|@WOMk! z?~l^6MJ@(7p~FO;H8+<%6Swz^zEPI{e){N!FUxFwuU{a})0xx=*pWPoG?36pb|no; z5H9B55f12;N5r(4S?Z~b!2zj2qCBeY1a;CU44fO*@$=f>kZEF5_LCWN? zuGn zph#I-fR;p%=~jZm3jrkZ7C1AvZ9x;17(ZOGw{ImMu>|wDJAQs3(Il9{lwIp^V2IK^ z&)DL!RUs>J7aSA3bd$6uyXj)p&uVrS;;C16fd$rcWyR zT)qI`lbO*H)EU#X^a@9ul@!@hgZ2RX{NjGZY!j}9(Ci1I zLJ6j|yt?ZOGY{l+ae-D4hq^aVu4ejmnB@=S&>aq`p)koTe zUxh%tPX&JN%f4jdXfU4ewf5I_xq7r3nF4WLF-94mhprXpd^d+74|qOz+uFg) z;1eVzuaxgcEY=*X0|bZ^f#Chp5iAHAs4t5KXF2Hbi=S-!d_hM&t?gvaHa>)k3~;!s z5))93Zh2ZXKXf`HLJ3*^7Z?oaP}88INs(nj^f!s-QA?V`iy=5>Pco+LaKpp;07crF zZ^2EC84_-bppVX2VFa!e^$gd+wlB~}yY=jQXmZJ;K4w0>aq}TO>oOU$mnWAXnoS?W z{aFehoZEWgsnMWzX&01KqTKxCp1S~Ris%-wdBDNZ|4{GXOTzr{*q~`p`F@UX&-?c} zJ3X+&89v_T867|A%;u=FwJ)J&O?`E{ojkL@ZuQl(*4})z5eU|9$Pw`>1Ag%E4gl`% z@!P!K9Nq#k$S?g)Su$+-^vjZWiEL&)tIZWxJ4)R zJS%mr5^NIkDAoR{44?#U;!T|Q1q9mNR)(OLHbwD`MsYFwhl4_+TTCCHMqONBdYzZs zpU$z}_Cl#lo4C>G?(WF7RieiXWx&rTA~@7U^A`se?HvR9u4C6~tg}b!LT^wnwmNRg z8WcXq16AZP#su{MOcz%KHHu<8g06Z@T{<@hGn@UGKQ1NV^l?3uD54}?w$_kjr9kMF zxlB%;-yHk|s+Zn%XTrcn_Nnm*#SY5OnoNhx3Y}X<{Gs zr=z5~K-D>$0tsbYOi$Z}r-I(1$D8F*+2R9mYivkNGo{QkZ(+y9iPmcMLH0VA>8Z64c!pgN?GP6l-~RoZCF8 zqAxlpapqIO8DfOn4bK{k4v#l%Ia~#$UAR5*AT3AYV!f=8%C&e^vB%oARsDRT&~?Hb z4V&!I#RG8n&FF%f319_BGx34Nu1G`7^}FI#_76zlJ3&mS%dwd36%#(d?H5|7_%;(* zAbauE;Gm7V>cJpv`1PBCI+{r@nXYQbfB5-}jiSSZU7c zoZZgSySVvd^XMq++%QgQvp4O*WY@sB6CTUzgq_0<1MrYQ(-w6+%DZz>vgYkQ(?{4h zudgoEOIjOWkj3=pr~mS~YPbHw!FvtMI)QWMGY)=DblShHTILj; zw=CH9iXlbME%|Ngs(d0Dn&FUak_0ADNc#=k?#9MZ`}SBUs}~GmO*gj?AfX_b1-L$O zfaXuZ4z;Q6h>{&xMTKd$y$HOaLWb$SXr#?eb4zJ%c58B^mg@Vyc+g1?8*$(m{tE0q zTqC(uSXo|S7Cicmo$AG(qaWjlaV%m<)dXX%Pgc&xkHL$;pMwp?}px<$<|Pql1ir_NdX7pIF;GY{Yp_Y zZe$P7YYK#+pXQ090*}RXO`%KdZz&(mCVxZdm#MkEpPo_IfRje^Ydo`_q`i8?u|7`k zqVHvJFRzHG<)f#)Si+Qc7})Gh99Gi5n`U@D>zH_#3~>{i?V|Vk@P2=tLig5j3z@a| z`2>BY0vqF)n1%A+-SxIjR)_{y^GY~$Qqs;22M2oQa)Dq;VTXBN4nR05xnRl)}1TEg^E&@6xoVlsS&MXk+M9vw7#UODx6yV`;TkYxPG4e>1C zvUiA1_OParrkj%Us=Wu}c=7r*b%jXTd9;X(1?w-LpBdn25UQJT&84Z;VW$2_X3}JE z?bECJUU>5@j1z0ZjHEqDki2g&0@Q5sbr zjAe0P>bjsxzJWLx{;60we+1c&hE6_}Wj)-&5U|?0=+CM2xP9ZRPw&52fJ*^gOU)O8 z#CmV%K5Vn2Y_dPYus~TYezv%?ynoVi>FWI8b4xX|)84oRIsl9N0;M0(D!CVYb;j~% zQwNN4hYzvQBR~6rqFTouMiRmg!3v)U#eM5*Z`Fc)=xf%WQxfI`J20NPC+U(Tuh-RwH}nLA6G z)H`mYS9Ip)mNbxO{)9ac+E#qu`U?`E>iTO|28y|&A%V37v(eqb>V-yTh~8RoSvK+x zHd2LWc{EefSQ%YP#eyc2&&OUCPks!ea6I6zT&ESB8`&@Le-}1_uVN%TUeRuWQ+#<4t^mtn(gO1=hg6Jf_p*I zYBg4TPT!h2h@%%JQI=2by(A3c@7jCPaGE$3?T59Az0up~7ms2p^ zLE~bXsawCw9)2J+iJ7cp?i2bedhP2=PSd%3>GS>36&!J?>qEIh~D6^)xocG&t zHR|YdO{}c`u?wBs04KO#qrOF(MN&=?p)JFRr_Y6v#pBna&z&m`$%ia@ZYQ2ILZC~| zVQW0Go=M@s!@1uB%=Qu8HYE7oqgF>fS|YGBTOP7dQDTf*{Xf??N*M=Yd3sF07IOA{ zx|OFbYy+H9J`1fcaR^YvEnHkObo3{TD47n|^04CLF*e*i92}!|kRu78zOy-c3lAeq z_$IpuzV|h`mL0RG_`UPl=`Tj41Jw9$$gCNS64j0uQqWa$ZMh7jK7cUt;tB!|Ht^k) z1_B&=hn6Rh_1 zk1aP;a>kbJ#8KtyvQ|Gns&RWMnk5p2jGMKu$^3pDVln+jFb(Ur{Q&cjKrp2Fv|ph=aU?I^D#vY<|+5_Mqe3f8|Cw*Qy|AedzH^bts7Tly;GPDL~1Yg8wM$K`F%p=HTT#w z6u(^xu`cOsCtd_w=Z*M01MzX8)DY{uzv2XrF+<%5IZ9TI#rYUjZo!LP($+A1XLE9f z1UZ}EW5A>amH)67_P-l_UVPA7urQ>`@6oz7#cGPo^PIMZ!gyr1pZ<`h31{U8T*qS0=CY} zDeO@V9FA@ulj#qNq#%}Q+jIA{|C>_$gwTs%)Uj-Y^5ex$?%JMjCArXC*}Asbx@X_w zzjIyDL)ZTUtK`Rrx6dfL&dEtx{p!RXkozNaJ`Qv0DzLuScD^^ZjmK)L%04EB5<7vC zsf9-u{ViaX+*aelXUCzl_Ff0OYvm#o%G{rTANc+f=L5}|s_og=wCV!2zb6~`id4XB zHr&#{LB)^8%M_kG(LY=z-YG?b*h)YmC6!64x}u%kN;kvbjq+d@5owH3wO&fJcx7r{ z9QBf1kUE7(2~^{6^ePr8d7Q$&@LDZ>_I>kvacGblzrT58PuaP`cC@K0!5h?w?FQ@q zR#K-hf{vRaJFRluT<0JZ5vo0n8O^q8TOQ8(+zA98lh>j(JcPNVr$=LJVRXLd=@67~ zAwS;4j7on)bbITJwrvMgMj}l=^O6Kff3RtyBZc8^oa*gvi`dQ_*mgDUE^h1&cyK!3 zbP727YBY!qs@*~^*ZkiKhxX1fDFU$)YiY3y3QppbANM|;)WGQ{KYX%2F#h-A17Fj< zK%9x2vFjNQ7U;<&2he?y2H{ps=3A##lvHe!j>^PtZgydU-(R4zC}2d^ermZ9%~S?b zBj!QD3!_^pqY2*y>8#;*J+1e5+!A$F8zIzun1mK1cB<~t?RVM;~gz&ipGxp4Pqi()PC1qcQWMz@{TyI$uE|v$$2m@bow+T|7?a# z03>9}9|A5(^enPL-t1d^`iV?HTb^L?!vnYCF=nSCL0-wWgKxLxN!z}`)jFPr6^uli zOxER!^KNO()WP`FqWf>80j#VuVr1C;bL+h;RKVxY7{fW*rde2wrb3lZH?-z4rF^4f4?CD8$G- zMb#aJ9h@++P3ofXM;zh%AfTncp&|l$GM^;n)4?oty0Uw9CEi)ENvnn|eUD_GD;9Ew z&P(eyWI#W(r)%!{J72xgrsC-}mE z$NGqp&lP~AQK4^89-HV(aC`frApVYZYEp-R1tKv zuJ0K@v})wR0&_IBqG)6{Pwyg-?&azYkY+OZXE)92^E9nQ50z*!us;dSePW^xQ&_(- ze?U~bD9Qh+eC~Q?Wl!f!dQ=U-rf#c$>`5pI&UmwCvfb#*piP#$cAtr<{q60fr3u1a zfQSBWEw)n28s{II3fb&ceHKLAP;hdOMesc#-0zRw zhd3@hzRXq%K_(KlclD9WrYs6M7{Pil0Z)$zMB;e)ALfkw}O|_ zO@jXCM4D-g=lncp{DqV-F~PUb%}|xp>#sZ0;M_x0_E@RD32UPie6VO0>L1 z`N`g~t?f!P>K9ri(bPj^R8+WA#Kj$dRrCZhelKlpGOVl-`Q-7!`C;c8^Xy@{1s=Hl zmFOcCBHcu@%c0+RalSo_w}y`~WLe+>Yvb>TBv`Od01!HSuo956(ksinmWr428AM(> zyN62Rfm-?CSW*^{DD2)t2sqge{nfOANCHvLw#9aN6#5*Ld^c}Z*feqqo3ID#&E7KH zJ^Sd59Y))<ovP57BdT_LEL%0JT$`WYxdxs`LSP@=YUAN%#Qlb>weZrRp4YVqTf}SCQksj; zt+T$pb2~Q8kQsR#v7S^sG8kU-`A+nVGFVz<&j8#d1Z0Gt*L%YWbxf)*0WaTA4GS5) zV$Z5zO&hkwQG+DG>x&c@M?ypzrhy)?+Ba1^q~kcwxty*>5x*9&8^2;zc#zG7pD~%< zdZtG(dW8GzUoAA$H72(`?C(YcAxa$&wuYd4?7%=uX!LFNpuWLXLAUIfm~1B{1_Cw! zT%^GY-%1mm7=sjT~#RbAcXcH7}SEj;#|7h8Ol z+uovQ! zQ$d3})MD87-0&-Ul&^bi57Ia6mG4&?L$ANAjniI@P9qIENku?j9J|)NjD|XpQNOgc zA^`FmDN*Mur}_aeu8HnE#Kz^yH0{#Ri=@>5TRK{<`;y9kb`07-ZmxHBCtOkU?w@x0l7AjW9~!V&BvCmXbX1&&_Z0{jD$E0Y7(QaPYE$%A}yK|mPz_71RQGCL7w z7~vo;pGgn@^r1Pph0}H-MJ?o7jp1%^^9svsRmJQSve1<8?U#mYI382DpH9pB!RHbv z$xGqtKJ>o~#H^fJX18%G(Lxt>W~NH2&`V^B{EQWhwRv2w>wAlNAO&)RU3Vg7LeiOj zBwD7Nr7xfBkYvQ~P9O-Z#lu%G`tkA}tSbAIZ;||?s>EYZL!*aP%ZYhkVq0C;v#C)P zHGu5{6pb4L?gJ~3Q@ksAshur+ZM#!~I@ym1 zXHA$JTCzTv>}=lv#0LqWf2IEXFJl6s^fGv-+2Evnu&e1+@F*L|6}z_{XZR3&_o7Jeh_^)_J9A zIggbqSX9mxj#I>sBvHFy@8oH=g`b5Z^oziO2RuAEN(>hWmSWBAk*PR7mW%2$QkvqMd1MnA1i;R`0^BMq>6M4Sfx$s4q5*=9I`vbD-H5c|wfL8-t z2p1zzE2E3kVFgWcl$`{Ib~8BgrksYJx?}VwQnG*!v??ma5-=q8iYn;yurTFxU>54% z?uZ<~4YB0^@#y0<9J?nGZ)6$=H?ArB8lRblKoy2@+1a3HV&isGyLMbgJ~U-u;1Pmu z=J(Xn=6$2g(Mhf5(4ET!3X5g#pM_ByttkOZkb3WSM#+UWC24t#t}9-e)A(AVpBoLv zGSI0h_IOV69%0Hb3Y@BhDF;2&9M1(oxRU!82-GP(YALsJu9?0&Hg+p_*e0xmQsvAr zZXPt|D7oTkntKi3x*%4NyoI`KFM#QxtpKsp?$Sp$(VWtdJ4o7A-4$dQ0f+THI|V>mrsKLd1jrgXSuKfGMsRb~|C0MOu6XHmn>}k_tmW-1Ua=V?9z)C0EhAoSR1mjm2Eu=N-CriT=z(Wo@z6w zefX~B^k3Hi`El=D*<(o|^Pl}I!fOVk9ROxb9TYSVSU2!#6@N;!9*fi_i!G9C=s!!< zIm9MpyTGX}2@)#W=k(@YB*$JlX*Dj&5c!zwLQO3$OmoBS$m?_=dUq2~@aQHvOUMI50#u_rZwQQ-B{Jnu@$a=Sx3K1`OFW68 zN6_4#NqCkyB=69zGJR=^-Myh|n+pFBTtZ;jFv0Sm4%3JDhmAj95(s$}mfyDL{%V4r z%=v&OpJJHM|M=r{%dDeg#}Nvra-oFue0=AYZ<$33fRZqi@{n`Umkuf+KGR;_5)|vw zsE>f8=r)6VdsJlPb&l^^KPi4xQOuY|MAV3)7A9UA#^iZSqq)Z^e+TCiG(@wVZX|V#lH8 zB*Ip0unTBH1kcqXIaicjFPjfFV!w+%>X8k25p?jClhB^0VM76j#?yM&l2CUzl7}n7 zgVMws3{se5#Vw6ZezYK152%a)B1!UP#_Vzuu1p3V5JXBChu`4x`?uk*#3xU&!s||i zARTl~pXXk4^VHY2*PA6;nooB$ts7mq&PIMQA$1xYY9~xU?Q$gNO+QwUZlWe|Kwu-&bUWI|wzJDKe{DULVKK z`R+e&>r@Dka9@1d+jLkTb2mMFEc8V%AfjAD`~k^qi-U^(zB`}ZCB1KPSA%1%Cw{HE zm*}JR)13V6yBA~Sd9DVtav#`Yym|02YS`z+4$PkPX0&4Dgg#hw2CBL4~`g3hQ*|_S;wM=?!ywBjuAP-=e zIx=VtLF?{T2@@+1EHdy#qn>miC+vZKlvb5n$QUYkT{);BogPv7Z z_pq@gZl8fDgyX@x4#G&V(~CKz&w!B{&g?feEp?h!ev5$edk@{;WA?va&#P)`FqJcT zON@ej0jNLa&J|iAB`Lup%C^y{Z*scg!LV@Q1mJRDTVdYa$z0O`UWY!@TcNK)UkDs{aVqM|nugugYOqQ3{EyxdDL&=C75LV@ zNa4xl^veWBZKgb&Lne#;*OfTOzR4kuCSiDVu2Z9VD#dxE-1t8le(^RKmwjwWB(V3q z#3r}$UP6hIA%~I{HDW==ZY_fk?MuvykB3{6k<#V64H#~ohmj{6y9nYX9HoSj;NBe7 zzWB+GaW-tJn2#--V1yiMa>wXDwHA`VJ$ui^I_2!O-<+|FIJp~04p0+&uB-rb;|vcp zBD*F`Vk#}q1flh=lmG~&<{+Hl?o#$a0O}S0&uH`R;Y4K{_jIqz?rAa?%s=jAU2L1i z;RZQ3YuA%!S9=R0?c-C{E!b=KKTpLHSQ(xT>P3_@Mim;9N`A%^K_B8 zyUTYD$1C?rvXIiYkMjrgty4U?E^%o4jghfiHYkB8w!!sd1y(F`%J0u3NoT_=s5m9$ z;u{V)TTQLYiEgI19UF4)_+;6+`EzeJJfZbo=Xnz*McKs0E3IJ`R6cO`)}4?5iZ3%s zzOn&MgE8%dDNS@UgCvTJAP#dMn?R1sSS~_>zzkH^aRQW%v%BXLqrL(CmN`y4xUvZL zi#swuEIz##tab2d`u`VGv2bP@PtNW``m$@S=vejuB=_#EE^unR8U^k zEqboq>c$mp7|uoNAwu1IRU7ZJ^Xqrssg{MAn(9-wZS~?W=r3w3jVBcWgg^_Sor8L# zn`NN+Sp+kzYc5u^+;+~dY(}F(TZI&K3MT@b*J{PTy5qUlw&_5BaL#CF``UyMR+d)I zAb7TWWI15d5j)zXNYkw+a&n?Y@fUh*x34TGRqVoN-bKG8w;VS_=zskFU65b%>_Kg% zU{5$yOVP;45P{y@e;9@%u2`LyJ~ZB<`j18aUrnBR5XlL`j&kMJWe)8R`2p zy65*XpeSU}BuI81c5b&PNH7_cI5rC3YkuiM(0*9q_LA3BPvuegND}v|hZA4<dgaKYvHLyVPjD}Gwn z`{DRh)Syfi1b;at0{n$G3rPvYN}X2fiJFLi;H2p{O4Qx1aL5cyZ5P? z6x0|15Tk8Yx6{-9``$dq%oqEiB2{~}0grZ#c(U~^v${{TS3E4e{>1_S$S*W3Y`yg>E!&rxGAquAgK_>vya6>N1xgUr0 zSJ-^i9v?(O(LRMH` zI3{OVeyD7!r6BY$CU{}n?3 zu)=WMu5!ZkRRO#X{o~_RvY@Y>2w9kDq=Uc0T(dmPVTQT)HJSPPZy^^GaM7U(7X~u& z2`FqF4)`hQyMZ(I<@7+rP!45pjS0vl4E$;#8v#5}___rmHJc$t(fpijYzSq9=eos$6G-W5=ppkbL9A5`Y>m1 zfloii1D3v{Kk2gnIiEkjtf1g#1ekn1RDBV0g|;lFh+ z{^|fhFc$EeRV*e1hCt*U6pM1_*A#zo+Mot(p0@yxtRkc{VptH63f>S+y{nuB615xgQ?YTw`47!9$u;^aBwA4cw8+cOc&=xF3@{S( zYSjWHOD8k1Uf9)_@S*Xkn7~r`x$xR&^yn-CPZh8aSI>qM{#Q6re;&95(MA9YumD}N z^D3vb`_6o~&?CO1Yw;ah23@#K3VTrMT569ybPy2GtU8(Y1f{$7%Lz_$iNCqDrK604 z?m1Dt%((l?3M?0y=ByPk~}5G$o3uuK!wV}uQ@Uq5bQ~3&Q&DvnfX1^y-nrx zKUw5|c4jf4V?hR7i9{a^2O2o#ShWkwa#{*)-|ld+(w6&+KwNz^O(0E!S(9Oi?e*Vo zE4?S20FmH*Ne@)kDL~r-G>INpVgT*3rqy52@ccjt@}`SF-YtjAqagrgY+T}|5Xdis z%ibA#=m$B*-owltMe}9(J8hI|{X3B8vW$47?2afFRR!VfNOTN(ZSI1J?ZxD8%C0t3 zH>R~Ni3NJk{=}Y(L!R$@2?^#M6TnIUwlcwF7!(0Sq>35P@LRu=Ws8&y(T9q&CzUj} z-UA;Wc^RzNFk18s6%}`ROz$CydNEcEmU+In7`{FIC)fG!G{CRZJsJFjg)0hZ-_b#Q zH^0`I<>S+0*=6=ycWsXvS9aZwZf{>N?$nf8l2Rzp0Ux&aVVdHDk?64p2l2-4-?Tyf z2B5y7`V%m?diXMDnmAlD3c>tcKSh-Dbyuw*_Z{D?2cA6 zCJCl6G-NEA=qC7aK{b@;1h9NhieCx;XA0@Ni0StLdg%65^|g!Y|F2-uPi;0}NT8|_ zA3o#)7RKkROB}nCDI~B7b`GnoNLeoJJ1VW_In;I!>i4=HS46KJ+I3G{Ba8|z2@CRF zVZhy1)2@&7x8=#K0?~c|E;_d4K%K9kc|m9Kb?@{gPP_Jq8!gnS_pr;*m^;C+X;FX? z{W%dmDEe5E_6hcRv*E5eytZB)wE0e3CM75N;$y6;6E%E$O}*1@T~}qRJ^!71*2DgH zRf8=?d}UZvC0LmHcOowQpL#1WCBUYJh7^g6oE!TQmn$40a|Pn3Yx?{zb@f5xK*kr|;cVPPrA z;QII^*tMs|cAW=jfydNKQubs)1D>}}Vsf>Mxnb333{~fi1uGLtJG~>cNbgpv=xj!} z1D|_Hx}8cko8$`7m{&`SmrP7gm|YIYY4eTGk9(*^RNBvuYLOQ!E5<#^fs>AdSGj6j z_8QCH%d1x*@?jH53^cU(H^1oe%B@t3k=ce@9g73F8e;hWPR_4#yE+XVA9ELr%!A-U zOi?decTMazoT<|g7NJ_(DOgcW3?BSmlE*;j)(p2Fs)}2Yu6N~3IKoBg=wkchi z?HE*@e=ArSW)Y7-dif>{Pe*!rxbKI9zT(bXwqT8*EJePvTL2b^piPR^$V-rAr)a0U znrpmhq@xyRD;Y@&-J}wa-#as8FFe3OL*w-O4AHQfnqj8dYER;j&vdD9r~G%iw+DuX zx+bRizf{z2{er>Ve=_Kv4ZJt*PVAC~oN1k%Z)AD-n`b00m5`YrH(QwN%P)7QJvVW# z*=EM}3CF|^En~Zd1-!Jy#`ae?MR%cOi@t~)w-KilAzprF)fvGkmJtF&TVpmG=($pU z<@{)S$}@$sZ~b%Bv?7UNTKkd;zVFvX`VV2auOFSot!uWi1}*B<(xw>^34%9kYI zV$|%v-IXE|NeDfC`g4c}f@rD}LjE2SSYn|vSvFC$=@Fp4Jf{}-X6-)if2%UGKjg); z?{acv^nN_#FmF}%y0k7tZl_mb3uEl);A8S24~rMgRKlQ0grAqMSwU)IXFNd&b^Gq= zUKdPUBxS2ic|RWP(L*9=>A>}w-u@~{d(B4@5$M1B)?icUxTXeLia^V)wc|y$v@-G>9^PusHy7o**5cjumt>I@tfF~x2X+3 zttabw7>%4}Sz_vV>7k>Xtc!=L@c8(k_C|-$6c3Nh*=F(xgo6c}qithFE8>NhgR+Ik zQXKyl#9Od=0a5b9M&V}+>02%^t*pS)1vyGOMStn2OX(=+X#B;xQgt%x;RIm4=Q zT{gTrhsH&W|+6u|bF; zSWlR_hwy~R;LvpBbl7(C;1uj3&x#4MA&M2|rNf?DD;R9T{?a9H;woJ@+HJc^B^i;Yb7gQwa*ep_5EGF(;T zzGC4hW{Dx8yIz`MrmHD>XM+CEIvdn8OG*+Hz3p}Rtv7pWPkOp`E~ov}D?kHcb#Cug z6VQ@R12Awydc{Uk>#sI+4d1IU$at7rZLMWro)wYx>g@ZREAp?8dAr(_(@iHqz1=Om ziw|H2iXL<#MGkF^+DODyI6%^m$t9X)=G5}Yo~;-?n@K)&IW}}RQH<@?N#5v%%EtC+ zMdaZ)F9WvT$n_0*To6DG-2lkd}3{1z$ z?I;)@G7XszsK~p+ql0^7tt;u>W{&d2N&bC}J=`fN-4{c;R*EGFc=%-*wJ%iByMcbx zUvz3C`vQ(v*ldKZf_7$ftU9quNSA!ngYBmV1XjvfAn}1`hCtYRc%%sz+neDfPS-t_ zLWK+y1lwID2m)hQPsVVub3@8*sr7EDtCIytN7mK0Y_`hJY?YjZ>Hd_?WvzJgcNbuv zn@U( zMwV&Fv=aFL=&kbS(}fDBmY~I0Xi^u1nIbs>uSb~J_1`%)Pz+2=ytLVI1@{56UD4fP z#>=Z}KF9#1V(0J(6jIAqXeiA)E9$3UW`mReA1WJGboL99R{+xROSf-!Z;QE65D zx;L_a?)UgOPi=`v%v*(XQSk95QK$!BH7%y7GSQT&DE_+*4HjByk(;Cak@d)=kGYy7 zuo#wbla`>!nmK%is?FjBfH9(vQT{E#O9`$dF=Us?^2*N~e}|=*W)sG%Q~B{6D~i?B z{s9W`2nFUnaEksN$xFh*e-s>uRNd840D?4Wk1yDeELx@s{ha?*XHE?1q$^Hr+F z$+iY4m)D^TU37uEtd?$bf~hs!nkW4CqXawOJ!zk;igvp`CtOb15sj+#umBtp(-*q| zUTbUFCdmDM<$X~GhM|jg7;8^jxbq4IonXXC&5A9ULe^ptkP%n2|9)INJ@_#Nb#mA2 ztRZ{7CnNMMt2bjzlsKRUU;@jRE_ZaJ=q`T%yTpkXdTin`IHLY59I#uh68CH^c#=i4_6}xU_m%IP_@o2M$?uY&Ppz62@{O4miHjwb= z7zzv|(eybyMZFUw(k|gK&C-7l4p=9OUQLqoG3_n@V zTjs`O0drwD(O~62TN*zf%SzGv^Bv;PzXoQ;@(J|XHjF06c)82nx@PaCO1@|+e0w}b zieap(gkhrGX}O&lUJQk5l5&U>yT5(X?lI%>qs0Wwdv~1i>fdR9cx-*V+3tDTjAK9h z)T8bw?+Va;4mtp(Qq>Vk&dH}#fI`K*yp9;#=UWy~A`OJ9?Iqukd2j&g`u(5n)y{~j z*$YJ+tU&9SN3?j7ttNyA$HuzKMrh?#RTp0DDCaSWiE(&SfhU{9o`U859Xc34hYZ`J z_D~j6NNCDve;OQ~T3)WAh>d!GQvZEG!2@mWZbzpfO)>B{Xa!HphW_&zs88A*KpBAl z9atp)xpPrJyes$LPXhm|#Q9&j2mkxD@&Equ|83a+3CaH{#{V4#UDwg$aLag1e0du<*{`e z^C$v%oAb_eN}6=|a+EB4`#^@Qa`xMvUG@JM3}72Bj7{V(ioDK`J&~QdJ*i?IplqQO zuv`yTA(xX5Qh~wpB3!rL+pBKZk0ZUl9%5i%kici5VqJSQ%&J|@d*m**F`U=wk55%> zx6nFi-^m7AvS3Ew4i@OH1x1`U+YsW%MV`kcFhGi} z3lrI{WWXV$^=#Y&6L*<*Gl^wYj}qCb;elNpW*r<3Dz4N4$kpko>(3$c>8s<46@VgW zUmwcRw3Ygw$DncasuM%0#oT$5_^moJ;&c+<<)|3-Bnu(iq{XAaB9|hiY26z4dd1Hz zY28=9)$DlfbT;|ng4|EsqP&f}GQag?e1Cuc+nk}AtD}P6{iRMGud_qaWa9sMNJHl! zDgqM*eh&{Hf9c|&S20gTHtO&QIMna&!=1O>8}~eb#R1w|l5*%IGiJYik|5$@P3yVa zD5s!MH@^Z)PVO2VRZHwPrVN#ml9nDcl{2=tXB=8*fr|D>k;o*6i{zzT$R1(l77~h$WwS%G4HBzw<)a*uQwY;s z0AZN*qx3QA^QH5cv|%B%OuQY{8=UVhJI`Zc(hs}=D_Q!fsYUkyD;3Y-pD7bwE|1kJs%&5 zVjQ~O$+9lfkS{?t`Q_*oWWC8w&&%6d9C;Gc5lnk-@3}xV)5a{m7f3Da_(*2JlHURJ z99gP6C&;L+{cQ8Vr0X(|cJ?7(QupQ*ykf}UB50qU0R7}^rq~zqb?J0wTb*`XCWY+bU$DW62bYA@vmw7hpZ$81a}npRPHd+7Sl< zI+yzMDbd}A%c?p5vbEJ!*OqX^*iSZ@ydjC2AMUlO@=5$g+mls5cP;0DvukV4M;R)5 zb-IusSXz z-g~WDyXv0I+O=y1`1wCma(unLdp|zlt5qd0G!kvn$~0ALN!AG*gq|(EidT^`@-B@7 zouZXzZ-!0@+|GURQ_sfd3h90!awcZTZ_30+ZGfOdfe63 z#o{ggzP(*_>~n*u5NI`j^Q?f`*{;l-2QsFG=2_0RIU%#NH~3zz`sd}S%~WA#k3;?Q z!YSIx+AwC@UEZE^+^e2Y3iQ{NTkoVbP{iefPyT~v@MGlf|ADUf(c{*SFaK}uFqvo>)vsCr!WxLrk1;2a z{x^^LzoYzPoQZz;G0r~%!2gG!*S(VFxRR#bIqUpwY(ukfGtbXR#GcIO{MpQ=@y^ zr#auL9%nNBdT1}#a?0bn{(^#{oc1?wJ}mq_>~>@HSlyz7?%eQKQXPi;BX0kQTR;36 z;nII3v~ULOPrgJaCUS2=6|-^mlSd8Fa{UBRl%kv8HM79T%vRp4sUHSj$LM{g8TNe7 z&#DOEf>3(Iqwllk z8+_d#bEg&vBxBmr+ekv?_|DiS{it=V^h_FLD-B& zdU;SaJ}XN&r}KtRUv-dQZEdYmh{))*R$4KcJeEIRwA9TgQ@%7mrJmY41tzDT1v_yQ z0M}1dTAcf0(m+0af8b?Gs%tN|TLja0j+Aun{wAfRG^45jEG)6BSXfw4KHc7`au$El zbDeli{!0c&;}jdWrs)1dJ#m_un=81uxP-e-R@gf_7LVo?78Vi^6G&4KrNE9$E5kF+ zG%l~{+1a@GcrFbMf{4&dWgjcOvvR3WPgO(1&9_QBxrL^<+N1QP7el04kPS&F{nTP# z9~;U0O)madNnG6%Y%O0c7D?N)P`J2!a3398PM2l4FE2P2jNIe!DaXNcA%LAiqN2s4 z=?0~qMnJ$TwjrJQj`0^0jov*su+ES8lW|kgk(Otz!;k@(Oio3t9AnXQGSI&?DI+!4 zVMoCH*>PF~m6~qW7{_Mw>K6i5uidz7T928PIT4rb`fI1Brw!Y)uPqm{k;E*i)XEU+ zqM+r)IV?bieY-Y0+Ae5X9|=aK?2I63V{d)#Wlc@ZY-?Hr}rD!&;_tT&fWx?Rpc{dhtNT-+waJh(+ogVONa#2$XtS88?- z-)`*985|OVL#ImEjyZk47C73L!Bu*9(@J1_W_ETQm5N7mMW69jpp3NV@SXBxl2=z( zr{ui!?T;W!JK`t?70J=e%k~Yj;|mq+9A~`B55%u-S2#alei zOw}#=*Y=W3IWb9SMQ*G@rVm*ekDp4Q9>(lDOUca4yeH$~-rU)_T-5&OzK_1XZX*Q! z+9IiU5tJ2(l(eg5##4PYZMk+P+B!NJn5!f2v$(m!?B5o57{9!|&g|N?8j!OBW^ZGf zhGz(vFDFd;FlRY%L%Ah(uk;X84+0%v5;)+h1QqCblNgZRPopV zw1=?M$M~hu_8e4v`PSN$?J=ocRnI>(<9uWEy??Zi#Nn%DKEgdD)15QUh2!21qnfMh z&r+#Fi?4jMvqc1%2Q+ncby-C$-!10(q6_|DU^MP7anx6^v$Hd<3lD>Ss-2)sph*j| zNXb30frYnv9arc>PAC=JDakrHebmI1%6q?XOvduL9jXfCt80*B5330gHCbMm0kxv# z$-F066uZ|2>fX?bQwa;MbDzx^931?|%{}6fE4r$zp4hzL-rZ`RB_u37vmA2b_&WOh z#GuW(;~ew-LB?-Z)t{yJ>-~vW=Sb6EcRV_s_@4k?$S~ZGLBU4Moq78&hD#*pOJ1?VR%@TiJ|O(FW5Lp}{>nmok(HHI zZMsoax+Mf5xns9}+JGMdR{R~lcWrDc%FBh{+$!;xuCO2M&kx4y2jlaD34k;Bkvac> z(LZQGA}s!(1%Eh$ADkK{g2%0mBjZ20o|^%BO-xKI4qPQqLCTL0kWzepetvNv1L>|e zGUR9~m1z*&Lh62Q!%JLk9d?_l0aSX#_CA%3|96jN1=6m{C|1qHW&+I; zzps~CoVvJ~ymXg&6g7)~_-d<9InMCM~8F^2$%UTe>0 zLKPt(-}qNh*5x`?!^9@Wf8@xKe}HHb!0B%5f=5xO?!Hf56B&i4TOvb-N~G<7P^fz^ z9`g3>+mCnB0CsR!fR!fmEFj2Wo8!epqoXzK^v`!g?P|pns6$ena>>rAIZG=S3iawh zc2HQLvQ1osoGA`OT{pN@S-niA9nEn1QYfbmbS z4B*D4IQmyD`b;m>FQPyb2Z`_Zhr0-1r-SMzM@!xJlQu?!E06)lA$W80Q#Fn}2M@3@ zIwwbT&z?Q3N3Wa)a1We(=Iaa>Pq+Mqm9UXzh9_HHh8#g?a6$xHt zy0f#h^X6b|pa7b{qgU{b0Q0dRm4;hW>p-m7b=~Z5L)RJ*n0X%iT${y*1=P9r3C?ok zyLctYj_8!5SKquN`kx>UpeG`*&d1je1g}R1Dl;sDR6xHJ_V=qSZFAWa92{)>*%Y`xp{-mh)sTyz?#nkGK4M&Aadxz- z(w|$Qr=ebZTW*mMpspawB}!lDftS)mNyv zoq)m1+k`3yW-jjZ`F9FIHd#yFm7Ip`zE{30_z@xSBEE?m_YyZUF)<#hQ&C;YzwzSk7ab%lWFnbj@AEif6x{J2!1KC_!F z=kT2#HM*$bAE@sx&Z6&X^TwAw;?4#Z+$~(bP;Wf7bd`rRWGebJyK7t#uC|070iy4( z&=DLVT0+&>7lsq2KP944l=k4xqwAI=()MKe(fp=7)S_VUztRK`+-4FH1~yq_x2Tm8 z#ooc8_isja6n%I46GToi6nMm)nRbit$iHoC3j&KM-Wac{Dkmo=Jsq`)P~O#n4O*Cb zNcvTtkRS4BrE|iGR>-pGK89C6x?9BZtcC{R2x;>=FoBCHmxBn7J1L`9fdZov2kmne zx}*&AW@=_mPCpb-B0Z#oF9~rE(E{RL1pN!OlOf0=5ZnYWL83n9*>QUfs;&3$vd1{FsZQDsr!#2yAqQKHxUhunK^@1$0<0RdmS-Z2oac$RqlR_ zDcjoW!t$6sP2@enhZ? z2kJSSLFF{LJWiG&yhxtIFiOi!W~+{(p@_vD4z0Rw`o4Q4MSNxGPI}IRu}TrrQc!6T zmcsj@`xeI51njE##H+1>=1tGQvh}@Y(N_Z9%UirOsT3^q4=qTLh7d~iq1Q*tI2b$# zf!pZf;tQLebP$yV7)e6-x|W&k32cb#=CG?(spm#R0~FF!h@ z9v4$sC?#lIU5>$?Oi*>B7BjCSQ8?#lWHOCbhS^Una6s{eN+x%Nw8=NStqmtWz7`*h z@e?qrd`!H7PL7o_1sfA`6Ouqe6}DCN*irR(l^Xo{sBEvxNO61qT;#K{Dc_!mQoTz% zE~VVEm3w;m)#-*y!U=wFvdyZ*gd0ng&NqrM)jWCkYKL&J(ypwoos5c<1ZBnG3eGe^ zWr?(GgO9H~pZV>&!1LDp)%I=YZvT8Z@F%SsHgj`~Q|2K7rE{vU?wukOf zdAxX~2%Q*v>(=V5tgM9GTrKN@3C}pyh?I_w%gs2W8@A&N`zkwnm_&+!V_Yj89}{DW z)0c*ZhR*BjN5GD0gUEgwTZ`!q^RCia+1W$UzS3`@s5=s*bYQe2SAD#2E*wiY@sJXq zlJni$jHLpNbLS$TKYwoHwVvdm7U9k)aOjYHb93|1z`(=SVGSFbv;w`<8zb+cz!`hB zrDkNP69Fz0OAa;RQabbV^VHi)R7U(JGY;wNPBe4PB4Dn|IuE;Xy=*8l2S_% z3(OO9Q`2)-uSOr+>sz!uYMmGpbJ{9L2T@JU);9fsaxka-eQ$3KJ-u-Hd>#2bYIJ@+ zjGQ9Rd4_ua{CQ4!q(IcvRL#?;Z!_0nS5{V1IAvvJ4@pYuAP3)udZSwkc%HM1i+^Y+&x6-bpFii<;@OdvnRyUh8_27B z-r719>eb$hOnKAo{4irAFg*V*6**2 zXuZqs{>;aRSvSvK{s9YLK#g(!2ltH|H>PVRSJu@9a^AUncR0J<%CB)SrgXbUq#QAP z4ILdxntC^7G3reSteoCO19_Hh0@zKhyno6JjsmNle#jCMo0=}*R)>UyE*MX(EGI~^ zG3Q=RnOM(2@~}YuKZM26W(0SP43|97eR%bcJv}o>$Oe(uXs2DdL)caXs@?N!d+#S* zOyt?2*e%9<_tf(8a?f^@c(s~ZTel+q#bFY3VqK(l8yPC;vwEqTNGAMWUwKs4)6m@= zdGgdLqbzNPo_#nW)Q02{iCCC`1*e0;!WtRIHIxcNN?pJDnKPc|=H?f4bhvZckN8!@ z)YqSrr&RS)n$7q4^7m^L0* z`r&7<4I4K$mzUp5(JS0lZXLlp`Mk~2HotRn-nHi!;$55D+Y=$M{z+o9+?g|U#l=fJ z0Y_!`-N@Gs{~}#IW&D>b=85+}b+FxBMpqsifvQed*>kT9K}ChE{BB?EU-q zDMESFldi4>J9sWdVlvl+imM|;`l83SZP~IfzmwOuj3c#mx7bDKx}WTBB9Xk}Q&M;f z;q&ndXh!qxbz9%K(rC0)EUK8pJ`_|`0ytScqdtGWzH!s0s-B58Z}Kju9QRp6`n_Og zdU_zIcsUvKKto%b8WY1Q|F*vVA(l2%o<7}otu0-)x3@P~%;u?{+l+>M^d?=Yy>(C6 zMEUuT6J5L!T}-7OhJ&Nxjq4vB#gss<)IvDg*!Xx0BxGw^$@sG;D1MU?Wt*~ZO`mSWl)3j8$L4*Td{jEefL%`)3! zNA4;#d#7hqXlUs1a7B6f1}rpjZDeBVxL!OkV0yDqFSm27BpZ$c(}~=mzSe`hd&QgK z#28k|)nsMwoH=tQ(|+(gy1IhjYuINGD=T5PFnCLm5aiQIn4b<8OcW?peEa z@v^ZeN*^6`i(Iv~Z{I#NJlu%Ythl74q>`GCc;J36F5ld!5!+ns(*7Il6VY@4(81i= zI#4L@aOq!LxrBg$ZT|X+B+P59KcH8&tIU+9* zq*Pg3+Y+l7*woT;z%0{ah0^J=HzI?#Xl0#{&~<|!l6IR(Z}R0iFB5-jx}EY?$kEAv~n8%d8~=S8soRRj+MALW2C;0k>)d zcbn8Lq|HL~oF^QZ-a$b@dDlPOx^m^pHg@(@U+IOjluz)ivm;t?RtE(H&Lc*_cS|@= zKZ|LwC<+MJ5gQlhGdS=wsl-Vzqy~n69)1B3(;f?mM>qVXSBLg|nsAz)C}UULb!17* zZ6Om&o(nXI2m@#ITsCkY3OgB zht3n)xTcm?kV^Qm1Ynj!M~~Vl`D|FXP7S^uiET9Ug*{Tv7wTkI3c}rH+e%)~hD*8F zV>%;}S%4WB8XRmuDpU?XXrp=YVq9LH1Q9G16cpBP6V&F}fhmc}LPdl@6x<{=eJ+yw zp21ES05(=p!*V?ww1$>ef~xfVX-tq$Vx*E6I=Qy7(qFn62z7&kva)~sXaGDKylT0DhF`JWoMPHs09t1@eayuT#q7Fn8aUa$(gT+;CAg;rFeE1^kcs+@f z^8)rYP)DX`pr+^<<|Mild5c!^MKp0}$UOHlFA??p{rx2z$3g+qqJY80#9L2QM%1Q+y z*FtjnPf&UJ@?=efj6UKGx?;Rw$_FD&b)>mzvb%o%18`8y$k=%D3J+p3ppce+rb!bn*_XT&&CD*H zl%6iIpOe$e@e=9!DNow?obMbb>9RhVOpc75jwk${Vj!=7<6slkob8b+qAzNK1m$E_ z=Ii`JLb%QBjXZ&A%m5k@>tldwlYt7j#l`21@2)15?39kc5jZxjmiqZOk^}hkc}w}5 z5D4+oMDmBXBzUka!-_3;Zr?^6Pe6e+@I?~@5<+%;N`+rOKB%m&X1i-jBJJcpaG)>v z8tmjEED>%B(=iKnjJBILQ#G#YInB(wA}4EIm>F)aua86#j0FgWKZdbm!JEbz+YVUw zOq06mAs!wjcJfjh2(d`mA+oQ3q9_y<+qQ4tj{)f^^RA^>>w3RelCLF}n#*mQg32`2M}Na+rih zh^Tc-7%JqHS>SK1vN4IwkUZzP&ZiS5Q#kIXx_|$E1tlefd6FJ3{%&%v`mtalq6nZv@>55d7CzdhR`dd?cDuOuJx68`u6AX%~un? zuciC)mAU_Wb@Qu(|5dK?@715L5E<+L{aJH# z$_dpB|MU5E=a*%72YY+Cb@ZECR6mic0gxH)^xU##i;&I7SG#>i2L|d(N<4_4L5;F{ zPTZ;ewrRl{79u78_fvADXEcXKuO2_Iu0DfFaq57dJZ`E#aLk8YCS`uAKk@nVbFW{& zUO@V_5_DBkLgE61UO8RPin#dxg-vwQ#bFkSZ@1fg`Ma0O@dB}=Kv`H^boktT0#nx< zq!1+r5;h%~FMn^c8gg}qEbbsL@0jOR0YSkmt4;~zA?22R4a{Ggm$NT?^Vh$7=)3{6 z-!Gq>oUEN=6}EoE28|0BwtaDjU~N6Tv6|W=W;U@%aNUQ*#kIiH`PCRVqP|U6oQ)Y4 zt%&rn$!)GP-Wuh76i#>}R85(~4B?*D5OE0lWA_fn+js9W<~ad`H4aj0q;UgqoJ`exbs%p3f-{~BE|GeJi$^f z**<$D<3Off=HTFnkmLjCYSky}qW<*4i4%XUU%y@mMR9zi8@_fHeX)Vq+v?v>w;&8g z3a}sG=sZvzF*$DEUb8$PCqqFlhU_L849Nh(k>w|8)mdwosaqYs9&G_*KE`CCLCS1JFtty`nv=aCOp z@_Us$dGX>!os_S^&IM>TlYrX^G)YZKX#q1dgPcHCOG|4d*W>F0N&>fpeKT(oT^ZT` z&6_tRTxOFzJw1s#APRD=yE!w*gnNcbVe31_;Qjk+*A^k;G zxONswv{=*_iXg~`hO#AVXDQ%)uu9}#W2|m&PGw^*>#yZP;-)`esrl);n2?y*GyEQb zN8mnJK9qm0(JKjj^kHssxkqZ<*O&FssrXQOSC~w9J))g?77oK1T$_yD2%^&rhH@Bs r#0!|V$TkipHal-M`DVRu+E++NKh8{Q3p+^>H8= literal 0 HcmV?d00001 diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml b/simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml new file mode 100644 index 0000000000000..e844b07ba0693 --- /dev/null +++ b/simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml @@ -0,0 +1,62 @@ +/**: + ros__parameters: + simulated_frame_id: "base_link" + origin_frame_id: "map" + vehicle_model_type: "ACTUATION_CMD_MECHANICAL" + initialize_source: "INITIAL_POSE_TOPIC" + timer_sampling_time_ms: 25 + add_measurement_noise: False + enable_road_slope_simulation: True + vel_lim: 50.0 + vel_rate_lim: 7.0 + steer_lim: 1.0 + steer_rate_lim: 5.0 + acc_time_delay: 0.1 + acc_time_constant: 0.1 + steer_time_delay: 0.0 + steer_time_constant: 0.001 + steer_dead_band: 0.0 + x_stddev: 0.0001 # x standard deviation for dummy covariance in map coordinate + y_stddev: 0.0001 # y standard deviation for dummy covariance in map coordinate + + accel_time_delay: 0.1 + accel_time_constant: 0.1 + brake_time_delay: 0.1 + brake_time_constant: 0.1 + accel_map_path: $(find-pkg-share simple_planning_simulator)/data/actuation_cmd_map/accel_map.csv + brake_map_path: $(find-pkg-share simple_planning_simulator)/data/actuation_cmd_map/brake_map.csv + + convert_accel_cmd: true + convert_brake_cmd: true + + convert_steer_cmd_method: "vgr" + vgr_coef_a: 15.713 + vgr_coef_b: 0.053 + vgr_coef_c: 0.042 + enable_pub_steer: true + + mechanical_params: + kp: 386.9151820510161 + ki: 5.460970982628869 + kd: 0.03550834077602694 + ff_gain: 0.03051963576179274 + angle_limit: 10.0 + rate_limit: 3.0 + dead_zone_threshold: 0.00708241866710033 + poly_a: 0.15251276182076065 + poly_b: -0.17301900674117585 + poly_c: 1.5896528355739639 + poly_d: 0.002300899817071436 + poly_e: -0.0418928856764797 + poly_f: 0.18449047960081838 + poly_g: -0.06320887302605509 + poly_h: 0.18696796150634806 + inertia: 25.17844747941984 + damping: 117.00653795106054 + stiffness: 0.17526182368541224 + friction: 0.6596571248682918 + vgr_coef_a: 2.4181735349544224 + vgr_coef_b: -0.013434076966833082 + vgr_coef_c: -0.033963661615283594 + steering_torque_limit: 30.0 + torque_delay_time: 0.0007641271506616108 diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 96cfa1587e646..685708844d32d 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -21,6 +21,7 @@ #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "rclcpp_components/register_node_macro.hpp" #include "simple_planning_simulator/vehicle_model/sim_model.hpp" +#include "simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp" #include #include @@ -147,7 +148,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt // Initial value must be set to current_input_command_ with the correct type. // If not, the vehicle_model will not be updated, and it will die when publishing the state. const auto vehicle_model_type_str = declare_parameter("vehicle_model_type", "IDEAL_STEER_VEL"); - if (vehicle_model_type_str == "ACTUATION_CMD") { + if (vehicle_model_type_str.find("ACTUATION_CMD") != std::string::npos) { current_input_command_ = ActuationCommandStamped(); sub_actuation_cmd_ = create_subscription( "input/actuation_command", QoS{1}, @@ -311,9 +312,7 @@ void SimplePlanningSimulator::initialize_vehicle_model(const std::string & vehic vehicle_model_ptr_ = std::make_shared( timer_sampling_time_ms_ / 1000.0, model_module_paths, model_param_paths, model_class_names); - } else if (vehicle_model_type_str == "ACTUATION_CMD") { - vehicle_model_type_ = VehicleModelType::ACTUATION_CMD; - + } else if (vehicle_model_type_str.find("ACTUATION_CMD") != std::string::npos) { // time delay const double accel_time_delay = declare_parameter("accel_time_delay"); const double accel_time_constant = declare_parameter("accel_time_constant"); @@ -323,37 +322,77 @@ void SimplePlanningSimulator::initialize_vehicle_model(const std::string & vehic // command conversion flag const bool convert_accel_cmd = declare_parameter("convert_accel_cmd"); const bool convert_brake_cmd = declare_parameter("convert_brake_cmd"); - const bool convert_steer_cmd = declare_parameter("convert_steer_cmd"); // actuation conversion map const std::string accel_map_path = declare_parameter("accel_map_path"); const std::string brake_map_path = declare_parameter("brake_map_path"); - // init vehicle model depending on convert_steer_cmd_method - if (convert_steer_cmd) { - const std::string convert_steer_cmd_method = - declare_parameter("convert_steer_cmd_method"); - if (convert_steer_cmd_method == "vgr") { - const double vgr_coef_a = declare_parameter("vgr_coef_a"); - const double vgr_coef_b = declare_parameter("vgr_coef_b"); - const double vgr_coef_c = declare_parameter("vgr_coef_c"); - vehicle_model_ptr_ = std::make_shared( - vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, - timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, - brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, - convert_brake_cmd, convert_steer_cmd, accel_map_path, brake_map_path, vgr_coef_a, - vgr_coef_b, vgr_coef_c); - } else if (convert_steer_cmd_method == "steer_map") { - const std::string steer_map_path = declare_parameter("steer_map_path"); - vehicle_model_ptr_ = std::make_shared( - vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, - timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, - brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, - convert_brake_cmd, convert_steer_cmd, accel_map_path, brake_map_path, steer_map_path); - } else { - throw std::invalid_argument( - "Invalid convert_steer_cmd_method: " + convert_steer_cmd_method); - } + if (vehicle_model_type_str == "ACTUATION_CMD") { + vehicle_model_type_ = VehicleModelType::ACTUATION_CMD; + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, + timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, + brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, + convert_brake_cmd, accel_map_path, brake_map_path); + } else if (vehicle_model_type_str == "ACTUATION_CMD_VGR") { + vehicle_model_type_ = VehicleModelType::ACTUATION_CMD_VGR; + const double vgr_coef_a = declare_parameter("vgr_coef_a"); + const double vgr_coef_b = declare_parameter("vgr_coef_b"); + const double vgr_coef_c = declare_parameter("vgr_coef_c"); + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, + timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, + brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, + convert_brake_cmd, accel_map_path, brake_map_path, vgr_coef_a, vgr_coef_b, vgr_coef_c); + } else if (vehicle_model_type_str == "ACTUATION_CMD_MECHANICAL") { + vehicle_model_type_ = VehicleModelType::ACTUATION_CMD_MECHANICAL; + const double vgr_coef_a = declare_parameter("vgr_coef_a"); + const double vgr_coef_b = declare_parameter("vgr_coef_b"); + const double vgr_coef_c = declare_parameter("vgr_coef_c"); + + const MechanicalParams mechanical_params = std::invoke([this]() -> MechanicalParams { + const std::string ns = "mechanical_params."; + MechanicalParams p; + p.kp = declare_parameter(ns + "kp"); + p.ki = declare_parameter(ns + "ki"); + p.kd = declare_parameter(ns + "kd"); + p.ff_gain = declare_parameter(ns + "ff_gain"); + p.angle_limit = declare_parameter(ns + "angle_limit"); + p.rate_limit = declare_parameter(ns + "rate_limit"); + p.dead_zone_threshold = declare_parameter(ns + "dead_zone_threshold"); + p.poly_a = declare_parameter(ns + "poly_a"); + p.poly_b = declare_parameter(ns + "poly_b"); + p.poly_c = declare_parameter(ns + "poly_c"); + p.poly_d = declare_parameter(ns + "poly_d"); + p.poly_e = declare_parameter(ns + "poly_e"); + p.poly_f = declare_parameter(ns + "poly_f"); + p.poly_g = declare_parameter(ns + "poly_g"); + p.poly_h = declare_parameter(ns + "poly_h"); + p.inertia = declare_parameter(ns + "inertia"); + p.damping = declare_parameter(ns + "damping"); + p.stiffness = declare_parameter(ns + "stiffness"); + p.friction = declare_parameter(ns + "friction"); + p.steering_torque_limit = declare_parameter(ns + "steering_torque_limit"); + p.torque_delay_time = declare_parameter(ns + "torque_delay_time"); + return p; + }); + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, + timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, + brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, + convert_brake_cmd, accel_map_path, brake_map_path, vgr_coef_a, vgr_coef_b, vgr_coef_c, + mechanical_params); + } else if (vehicle_model_type_str == "ACTUATION_CMD_STEER_MAP") { + vehicle_model_type_ = VehicleModelType::ACTUATION_CMD_STEER_MAP; + const std::string steer_map_path = declare_parameter("steer_map_path"); + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, + timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, + brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, + convert_brake_cmd, accel_map_path, brake_map_path, steer_map_path); + } else { + throw std::invalid_argument( + "Invalid ACTUATION_CMD vehicle_model_type: " + vehicle_model_type_str); } } else { throw std::invalid_argument("Invalid vehicle_model_type: " + vehicle_model_type_str); @@ -710,7 +749,10 @@ void SimplePlanningSimulator::set_initial_state(const Pose & pose, const Twist & vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED || vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED_WO_FALL_GUARD || vehicle_model_type_ == VehicleModelType::DELAY_STEER_MAP_ACC_GEARED || - vehicle_model_type_ == VehicleModelType::ACTUATION_CMD) { + vehicle_model_type_ == VehicleModelType::ACTUATION_CMD || + vehicle_model_type_ == VehicleModelType::ACTUATION_CMD_VGR || + vehicle_model_type_ == VehicleModelType::ACTUATION_CMD_MECHANICAL || + vehicle_model_type_ == VehicleModelType::ACTUATION_CMD_STEER_MAP) { state << x, y, yaw, vx, steer, accx; } vehicle_model_ptr_->setState(state); diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp new file mode 100644 index 0000000000000..0977cd9e25a92 --- /dev/null +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp @@ -0,0 +1,352 @@ +// Copyright 2024 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 "simple_planning_simulator/utils/mechanical_controller.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace autoware::simple_planning_simulator::utils::mechanical_controller +{ + +using DelayBuffer = std::deque>; +using DelayOutput = std::pair, DelayBuffer>; + +DelayOutput delay( + const double signal, const double delay_time, const DelayBuffer & buffer, + const double elapsed_time) +{ + DelayBuffer new_buffer = buffer; + + new_buffer.push_back(std::make_pair(signal, elapsed_time)); + + if (!buffer.empty() && (elapsed_time - new_buffer.front().second) >= delay_time) { + const double delayed_signal = new_buffer.front().first; + new_buffer.pop_front(); + return {delayed_signal, new_buffer}; + } else { + return {std::nullopt, new_buffer}; + } +} + +double sign(const double x) +{ + return (x >= 0.0) ? 1.0 : -1.0; +} + +double apply_limits( + const double current_angle, const double previous_angle, const double angle_limit, + const double rate_limit, const double dt) +{ + const double angle_diff = std::clamp(current_angle, -angle_limit, angle_limit) - previous_angle; + const double rate_limited_diff = std::clamp(angle_diff, -rate_limit * dt, rate_limit * dt); + return std::clamp(previous_angle + rate_limited_diff, -angle_limit, angle_limit); +} + +double feedforward(const double input_angle, const double ff_gain) +{ + return ff_gain * input_angle; +} + +double polynomial_transform( + const double torque, const double speed, const double a, const double b, const double c, + const double d, const double e, const double f, const double g, const double h) +{ + return a * torque * torque * torque + b * torque * torque + c * torque + + d * speed * speed * speed + e * speed * speed + f * speed + g * torque * speed + h; +} + +PIDController::PIDController(const double kp, const double ki, const double kd) +: kp_(kp), ki_(ki), kd_(kd), state_{0.0, 0.0} +{ +} + +double PIDController::compute( + const double error, const double integral, const double prev_error, const double dt) const +{ + const double p_term = kp_ * error; + const double i_term = ki_ * integral; + const double d_term = dt < 1e-6 ? 0.0 : kd_ * (error - prev_error) / dt; + + return p_term + i_term + d_term; +} + +void PIDController::update_state(const double error, const double dt) +{ + state_.integral += error * dt; + state_.error = error; +}; + +void PIDController::update_state( + const double k1_error, const double k2_error, const double k3_error, const double k4_error, + const double dt) +{ + state_.error = (k1_error + 2 * k2_error + 2 * k3_error + k4_error) / 6.0; + state_.integral += state_.error * dt; +}; + +PIDControllerState PIDController::get_state() const +{ + return state_; +} + +void PIDController::clear_state() +{ + state_ = {0.0, 0.0}; +} + +SteeringDynamics::SteeringDynamics( + const double angular_position, const double angular_velocity, const double inertia, + const double damping, const double stiffness, const double friction, + const double dead_zone_threshold) +: state_{angular_position, angular_velocity, false}, + inertia_(inertia), + damping_(damping), + stiffness_(stiffness), + friction_(friction), + dead_zone_threshold_(dead_zone_threshold) +{ +} + +bool SteeringDynamics::is_in_dead_zone( + const SteeringDynamicsState & state, const double input_torque) const +{ + bool is_in_dead_zone = state.is_in_dead_zone; + const int rotation_direction = sign(state.angular_velocity); + const int input_direction = sign(input_torque); + + if (input_direction != rotation_direction && std::abs(input_torque) < dead_zone_threshold_) { + return true; + } + + if (is_in_dead_zone) { + return !(dead_zone_threshold_ <= std::abs(input_torque)); + } + + return false; +} + +SteeringDynamicsDeltaState SteeringDynamics::calc_model( + const SteeringDynamicsState & state, const double input_torque) const +{ + const double friction_force = friction_ * sign(state.angular_velocity); + const double angular_acceleration = (input_torque - damping_ * state.angular_velocity - + stiffness_ * state.angular_position - friction_force) / + inertia_; + + const double d_angular_velocity = angular_acceleration; + const double d_angular_position = state.angular_velocity; + + return {d_angular_position, d_angular_velocity}; +} + +void SteeringDynamics::set_state(const SteeringDynamicsState & state) +{ + state_ = state; +} + +SteeringDynamicsState SteeringDynamics::get_state() const +{ + return state_; +} + +void SteeringDynamics::set_steer(const double steer) +{ + state_.angular_position = steer; +} + +void SteeringDynamics::clear_state() +{ + state_ = {0.0, 0.0, false}; +} + +MechanicalController::MechanicalController(const MechanicalParams & params) +: pid_(params.kp, params.ki, params.kd), + steering_dynamics_( + 0.0, 0.0, params.inertia, params.damping, params.stiffness, params.friction, + params.dead_zone_threshold), + params_(params) +{ +} + +void MechanicalController::clear_state() +{ + delay_buffer_.clear(); + pid_.clear_state(); + steering_dynamics_.clear_state(); +} + +void MechanicalController::set_steer(const double steer) +{ + steering_dynamics_.set_steer(steer); +} + +[[maybe_unused]] double MechanicalController::update_euler( + const double input_angle, const double speed, const double prev_input_angle, const double dt) +{ + const auto dynamics_state = steering_dynamics_.get_state(); + + const auto d_state = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, steering_dynamics_); + + const double d_angular_position = d_state.dynamics_d_state.d_angular_position; + const double d_angular_velocity = d_state.dynamics_d_state.d_angular_velocity; + + auto dynamics_state_new = dynamics_state; + dynamics_state_new.angular_position = std::clamp( + dynamics_state.angular_position + d_angular_position * dt, -params_.angle_limit, + params_.angle_limit); + dynamics_state_new.angular_velocity = std::clamp( + dynamics_state.angular_velocity + d_angular_velocity * dt, -params_.rate_limit, + params_.rate_limit); + dynamics_state_new.is_in_dead_zone = d_state.is_in_dead_zone; + steering_dynamics_.set_state(dynamics_state_new); + + pid_.update_state(d_state.pid_error, dt); + delay_buffer_ = d_state.delay_buffer; + + return dynamics_state_new.angular_position; +} + +double MechanicalController::update_runge_kutta( + const double input_angle, const double speed, const double prev_input_angle, const double dt) +{ + const auto dynamics_state = steering_dynamics_.get_state(); + + // NOTE: k1, k2, k3, k4 suffix denote the intermediate points of RK4 + const auto k1 = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, steering_dynamics_); + + auto dynamics_for_k2 = steering_dynamics_; + auto dynamics_state_for_k2 = steering_dynamics_.get_state(); + dynamics_state_for_k2.angular_position = + dynamics_state.angular_position + k1.dynamics_d_state.d_angular_position * 0.5 * dt; + dynamics_state_for_k2.angular_velocity = + dynamics_state.angular_velocity + k1.dynamics_d_state.d_angular_velocity * 0.5 * dt; + dynamics_for_k2.set_state(dynamics_state_for_k2); + const auto k2 = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, dynamics_for_k2); + + auto dynamics_for_k3 = steering_dynamics_; + auto dynamics_state_for_k3 = steering_dynamics_.get_state(); + dynamics_state_for_k3.angular_position = + dynamics_state.angular_position + k2.dynamics_d_state.d_angular_position * 0.5 * dt; + dynamics_state_for_k3.angular_velocity = + dynamics_state.angular_velocity + k2.dynamics_d_state.d_angular_velocity * 0.5 * dt; + dynamics_for_k3.set_state(dynamics_state_for_k3); + const auto k3 = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, dynamics_for_k3); + + auto dynamics_for_k4 = steering_dynamics_; + auto dynamics_state_for_k4 = steering_dynamics_.get_state(); + dynamics_state_for_k4.angular_position = + dynamics_state.angular_position + k3.dynamics_d_state.d_angular_position * dt; + dynamics_state_for_k4.angular_velocity = + dynamics_state.angular_velocity + k3.dynamics_d_state.d_angular_velocity * dt; + dynamics_for_k4.set_state(dynamics_state_for_k4); + const auto k4 = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, dynamics_for_k4); + + const double d_angular_position = + (k1.dynamics_d_state.d_angular_position + 2.0 * k2.dynamics_d_state.d_angular_position + + 2.0 * k3.dynamics_d_state.d_angular_position + k4.dynamics_d_state.d_angular_position) / + 6.0; + const double d_angular_velocity = + (k1.dynamics_d_state.d_angular_velocity + 2.0 * k2.dynamics_d_state.d_angular_velocity + + 2.0 * k3.dynamics_d_state.d_angular_velocity + k4.dynamics_d_state.d_angular_velocity) / + 6.0; + + // update steering dynamics/controller internal state + auto dynamics_state_new = dynamics_state; + dynamics_state_new.angular_position = std::clamp( + dynamics_state.angular_position + d_angular_position * dt, -params_.angle_limit, + params_.angle_limit); + dynamics_state_new.angular_velocity = std::clamp( + dynamics_state.angular_velocity + d_angular_velocity * dt, -params_.rate_limit, + params_.rate_limit); + pid_.update_state(k1.pid_error, k2.pid_error, k3.pid_error, k4.pid_error, dt); + if ( + k1.delay_buffer.empty() || k2.delay_buffer.empty() || k3.delay_buffer.empty() || + k4.delay_buffer.empty()) { + // This condition is assumed to never be met because it is always pushed by + // the delay() function. + return dynamics_state.angular_position; + } + const double delayed_signal = + (k1.delay_buffer.back().first + 2.0 * k2.delay_buffer.back().first + + 2.0 * k3.delay_buffer.back().first + k4.delay_buffer.back().first) / + 6.0; + const double elapsed_time = delay_buffer_.empty() ? dt : delay_buffer_.back().second + dt; + delay_buffer_ = + delay(delayed_signal, params_.torque_delay_time, delay_buffer_, elapsed_time).second; + dynamics_state_new.is_in_dead_zone = + steering_dynamics_.is_in_dead_zone(dynamics_state_new, delayed_signal); + steering_dynamics_.set_state(dynamics_state_new); + + return dynamics_state_new.angular_position; +} + +StepResult MechanicalController::run_one_step( + const double input_angle, const double speed, const double prev_input_angle, const double dt, + const DelayBuffer & delay_buffer, const PIDController & pid, + const SteeringDynamics & dynamics) const +{ + const auto dynamics_state = dynamics.get_state(); + const auto pid_state = pid.get_state(); + + const double limited_input_angle = + apply_limits(input_angle, prev_input_angle, params_.angle_limit, params_.rate_limit, dt); + + const double ff_torque = feedforward(limited_input_angle, params_.ff_gain); + + const double pid_error = limited_input_angle - dynamics_state.angular_position; + + const double pid_torque = + pid.compute(pid_error, pid_state.integral + pid_error * dt, pid_state.error, dt); + + const double total_torque = ff_torque + pid_torque; + + // NOTE: do not distinguish between forward and backward driving + const double steering_torque = std::clamp( + polynomial_transform( + total_torque, std::abs(speed), params_.poly_a, params_.poly_b, params_.poly_c, params_.poly_d, + params_.poly_e, params_.poly_f, params_.poly_g, params_.poly_h), + -params_.steering_torque_limit, params_.steering_torque_limit); + + const double elapsed_time = delay_buffer.empty() ? dt : delay_buffer.back().second + dt; + const auto [delayed_torque_opt, delay_buffer_new] = + delay(steering_torque, params_.torque_delay_time, delay_buffer, elapsed_time); + + if (!delayed_torque_opt.has_value()) { + return {delay_buffer_new, pid_error, {0.0, 0.0}, dynamics_state.is_in_dead_zone}; + } + + const bool is_in_dead_zone = dynamics.is_in_dead_zone(dynamics_state, steering_torque); + if (is_in_dead_zone) { + return {delay_buffer_new, pid_error, {0.0, 0.0}, true}; + } + + const auto d_state = dynamics.calc_model(dynamics.get_state(), steering_torque); + + return {delay_buffer_new, pid_error, d_state, false}; +} + +} // namespace autoware::simple_planning_simulator::utils::mechanical_controller diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp index 74ad765687a2e..469c30dc4f0cf 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp @@ -108,43 +108,13 @@ double BrakeMap::getBrake(const double acc, double vel) const return autoware::interpolation::lerp(interpolated_acc_vec, brake_indices, acc); } -// steer map sim model +// convert only longitudinal actuation command SimModelActuationCmd::SimModelActuationCmd( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double accel_delay, double accel_time_constant, double brake_delay, double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, - bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd, - std::string accel_map_path, std::string brake_map_path, std::string steer_map_path) -: SimModelInterface(6 /* dim x */, 5 /* dim u */), - MIN_TIME_CONSTANT(0.03), - vx_lim_(vx_lim), - vx_rate_lim_(vx_rate_lim), - steer_lim_(steer_lim), - steer_rate_lim_(steer_rate_lim), - wheelbase_(wheelbase), - accel_delay_(accel_delay), - accel_time_constant_(std::max(accel_time_constant, MIN_TIME_CONSTANT)), - brake_delay_(brake_delay), - brake_time_constant_(std::max(brake_time_constant, MIN_TIME_CONSTANT)), - steer_delay_(steer_delay), - steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), - steer_bias_(steer_bias) -{ - initializeInputQueue(dt); - convert_accel_cmd_ = convert_accel_cmd && accel_map_.readActuationMapFromCSV(accel_map_path); - convert_brake_cmd_ = convert_brake_cmd && brake_map_.readActuationMapFromCSV(brake_map_path); - convert_steer_cmd_ = convert_steer_cmd && steer_map_.readActuationMapFromCSV(steer_map_path); - actuation_sim_type_ = ActuationSimType::STEER_MAP; -} - -// VGR sim model -SimModelActuationCmd::SimModelActuationCmd( - double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, - double dt, double accel_delay, double accel_time_constant, double brake_delay, - double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, - bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd, - std::string accel_map_path, std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, - double vgr_coef_c) + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path) : SimModelInterface(6 /* dim x */, 5 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -159,15 +129,12 @@ SimModelActuationCmd::SimModelActuationCmd( steer_delay_(steer_delay), steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), steer_bias_(steer_bias), - convert_steer_cmd_(convert_steer_cmd), - vgr_coef_a_(vgr_coef_a), - vgr_coef_b_(vgr_coef_b), - vgr_coef_c_(vgr_coef_c) + convert_accel_cmd_(convert_accel_cmd), + convert_brake_cmd_(convert_brake_cmd) { initializeInputQueue(dt); convert_accel_cmd_ = convert_accel_cmd && accel_map_.readActuationMapFromCSV(accel_map_path); convert_brake_cmd_ = convert_brake_cmd && brake_map_.readActuationMapFromCSV(brake_map_path); - actuation_sim_type_ = ActuationSimType::VGR; } double SimModelActuationCmd::getX() @@ -222,6 +189,7 @@ void SimModelActuationCmd::update(const double & dt) delayed_input(IDX_U::SLOPE_ACCX) = input_(IDX_U::SLOPE_ACCX); const auto prev_state = state_; + updateRungeKutta(dt, delayed_input); // take velocity/steer limit explicitly @@ -248,36 +216,32 @@ void SimModelActuationCmd::initializeInputQueue(const double & dt) std::fill(steer_input_queue_.begin(), steer_input_queue_.end(), 0.0); } -Eigen::VectorXd SimModelActuationCmd::calcModel( +Eigen::VectorXd SimModelActuationCmd::calcLongitudinalModel( const Eigen::VectorXd & state, const Eigen::VectorXd & input) { using autoware_vehicle_msgs::msg::GearCommand; const double vel = std::clamp(state(IDX::VX), -vx_lim_, vx_lim_); const double acc = std::clamp(state(IDX::ACCX), -vx_rate_lim_, vx_rate_lim_); - const double yaw = state(IDX::YAW); const double steer = state(IDX::STEER); - + const double yaw = state(IDX::YAW); const double accel = input(IDX_U::ACCEL_DES); const double brake = input(IDX_U::BRAKE_DES); const auto gear = input(IDX_U::GEAR); - // 1) calculate acceleration by accel and brake command + // calculate acceleration by accel and brake command const double acc_des_wo_slope = std::clamp( std::invoke([&]() -> double { - // Select the non-zero value between accel and brake and calculate the acceleration if (convert_accel_cmd_ && accel > 0.0) { - // convert accel command to acceleration return accel_map_.getControlCommand(accel, vel); } else if (convert_brake_cmd_ && brake > 0.0) { - // convert brake command to acceleration return brake_map_.getControlCommand(brake, vel); } else { - // if conversion is disabled, accel command is directly used as acceleration return accel; } }), -vx_rate_lim_, vx_rate_lim_); + // add slope acceleration considering the gear state const double acc_by_slope = input(IDX_U::SLOPE_ACCX); const double acc_des = std::invoke([&]() -> double { @@ -290,36 +254,31 @@ Eigen::VectorXd SimModelActuationCmd::calcModel( }); const double acc_time_constant = accel > 0.0 ? accel_time_constant_ : brake_time_constant_; - // 2) calculate steering rate by steer command - const double steer_rate = std::clamp( - std::invoke([&]() -> double { - // if conversion is enabled, calculate steering rate from steer command - if (convert_steer_cmd_) { - if (actuation_sim_type_ == ActuationSimType::VGR) { - // convert steer wheel command to steer rate - const double steer_des = - calculateSteeringTireCommand(vel, steer, input(IDX_U::STEER_DES)); - return -(getSteer() - steer_des) / steer_time_constant_; - } else if (actuation_sim_type_ == ActuationSimType::STEER_MAP) { - // convert steer command to steer rate - return steer_map_.getControlCommand(input(IDX_U::STEER_DES), vel) / steer_time_constant_; - } - } - // otherwise, steer command is desired steering angle, so calculate steering rate from the - // difference between the desired steering angle and the current steering angle. - const double steer_des = std::clamp(input(IDX_U::STEER_DES), -steer_lim_, steer_lim_); - return -(getSteer() - steer_des) / steer_time_constant_; - }), - -steer_rate_lim_, steer_rate_lim_); + // calculate derivative of longitudinal states except steering + Eigen::VectorXd d_longitudinal_state = Eigen::VectorXd::Zero(dim_x_); + d_longitudinal_state(IDX::X) = vel * cos(yaw); + d_longitudinal_state(IDX::Y) = vel * sin(yaw); + d_longitudinal_state(IDX::YAW) = vel * std::tan(steer) / wheelbase_; + d_longitudinal_state(IDX::VX) = acc; + d_longitudinal_state(IDX::ACCX) = -(acc - acc_des) / acc_time_constant; - Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); - d_state(IDX::X) = vel * cos(yaw); - d_state(IDX::Y) = vel * sin(yaw); - d_state(IDX::YAW) = vel * std::tan(steer) / wheelbase_; - d_state(IDX::VX) = acc; - d_state(IDX::STEER) = steer_rate; - d_state(IDX::ACCX) = -(acc - acc_des) / acc_time_constant; + return d_longitudinal_state; +} +double SimModelActuationCmd::calcLateralModel( + [[maybe_unused]] const double steer, const double steer_input, [[maybe_unused]] const double vel) +{ + const double steer_rate = std::clamp( + -(getSteer() - steer_input) / steer_time_constant_, -steer_rate_lim_, steer_rate_lim_); + return steer_rate; +} + +Eigen::VectorXd SimModelActuationCmd::calcModel( + const Eigen::VectorXd & state, const Eigen::VectorXd & input) +{ + Eigen::VectorXd d_state = calcLongitudinalModel(state, input); + d_state(IDX::STEER) = + calcLateralModel(state(IDX::STEER), input(IDX_U::STEER_DES), state(IDX::VX)); return d_state; } @@ -383,20 +342,57 @@ SimModelActuationCmd::getActuationStatus() const actuation_status.status.brake_status = brake_map_.getBrake(acc_state, vel_state); } - if (convert_steer_cmd_) { - if (actuation_sim_type_ == ActuationSimType::VGR) { - actuation_status.status.steer_status = - calculateSteeringWheelState(vel_state, state_(IDX::STEER)); - } - // NOTE: Conversion by steer map is not supported - // else if (actuation_sim_type_ == ActuationSimType::STEER_MAP) {} + return actuation_status; +} + +/* ------ SteerMap model ----- */ +SimModelActuationCmdSteerMap::SimModelActuationCmdSteerMap( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, std::string steer_map_path) +: SimModelActuationCmd( + vx_lim, steer_lim, vx_rate_lim, steer_rate_lim, wheelbase, dt, accel_delay, accel_time_constant, + brake_delay, brake_time_constant, steer_delay, steer_time_constant, steer_bias, + convert_accel_cmd, convert_brake_cmd, accel_map_path, brake_map_path) +{ + initializeInputQueue(dt); + if (!steer_map_.readActuationMapFromCSV(steer_map_path)) { + throw std::runtime_error("Failed to read steer map from " + steer_map_path); } +} - return actuation_status; +double SimModelActuationCmdSteerMap::calcLateralModel( + [[maybe_unused]] const double steer, const double steer_input, const double vel) +{ + const double steer_rate = std::clamp( + steer_map_.getControlCommand(steer_input, vel) / steer_time_constant_, -steer_rate_lim_, + steer_rate_lim_); + + return steer_rate; } +/* ---------------------------------------- */ -/* ------ Functions for VGR sim model ----- */ -double SimModelActuationCmd::calculateSteeringTireCommand( +/* ------ VGR model ----- */ +SimModelActuationCmdVGR::SimModelActuationCmdVGR( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, double vgr_coef_c) +: SimModelActuationCmd( + vx_lim, steer_lim, vx_rate_lim, steer_rate_lim, wheelbase, dt, accel_delay, accel_time_constant, + brake_delay, brake_time_constant, steer_delay, steer_time_constant, steer_bias, + convert_accel_cmd, convert_brake_cmd, accel_map_path, brake_map_path), + vgr_coef_a_(vgr_coef_a), + vgr_coef_b_(vgr_coef_b), + vgr_coef_c_(vgr_coef_c) +{ + initializeInputQueue(dt); +} + +double SimModelActuationCmdVGR::calculateSteeringTireCommand( const double vel, const double steer, const double steer_wheel_des) const { // steer_tire_state -> steer_wheel_state @@ -408,17 +404,114 @@ double SimModelActuationCmd::calculateSteeringTireCommand( return steer_wheel_des / adaptive_gear_ratio; } -double SimModelActuationCmd::calculateSteeringWheelState( +double SimModelActuationCmdVGR::calculateSteeringWheelState( const double vel, const double steer_state) const { return (vgr_coef_a_ + vgr_coef_b_ * vel * vel) * steer_state / (1.0 + vgr_coef_c_ * std::abs(steer_state)); } -double SimModelActuationCmd::calculateVariableGearRatio( +double SimModelActuationCmdVGR::calculateVariableGearRatio( const double vel, const double steer_wheel) const { return std::max( 1e-5, vgr_coef_a_ + vgr_coef_b_ * vel * vel - vgr_coef_c_ * std::fabs(steer_wheel)); } + +double SimModelActuationCmdVGR::calcLateralModel( + const double steer, const double steer_input, const double vel) +{ + const double steer_des = calculateSteeringTireCommand(vel, steer, steer_input); + const double steer_rate = + std::clamp(-(getSteer() - steer_des) / steer_time_constant_, -steer_rate_lim_, steer_rate_lim_); + return steer_rate; +} +/* ---------------------------------------- */ + +/* ------ MECHANICAL model ----- */ +SimModelActuationCmdMechanical::SimModelActuationCmdMechanical( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, double vgr_coef_c, + MechanicalParams mechanical_params) +: SimModelActuationCmdVGR( + vx_lim, steer_lim, vx_rate_lim, steer_rate_lim, wheelbase, dt, accel_delay, accel_time_constant, + brake_delay, brake_time_constant, steer_delay, steer_time_constant, steer_bias, + convert_accel_cmd, convert_brake_cmd, accel_map_path, brake_map_path, vgr_coef_a, vgr_coef_b, + vgr_coef_c), + mechanical_controller_(std::make_unique(mechanical_params)) +{ +} + +void SimModelActuationCmdMechanical::update(const double & dt) +{ + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + accel_input_queue_.push_back(input_(IDX_U::ACCEL_DES)); + delayed_input(IDX_U::ACCEL_DES) = accel_input_queue_.front(); + accel_input_queue_.pop_front(); + + brake_input_queue_.push_back(input_(IDX_U::BRAKE_DES)); + delayed_input(IDX_U::BRAKE_DES) = brake_input_queue_.front(); + brake_input_queue_.pop_front(); + + steer_input_queue_.push_back(input_(IDX_U::STEER_DES)); + delayed_input(IDX_U::STEER_DES) = steer_input_queue_.front(); + steer_input_queue_.pop_front(); + + delayed_input(IDX_U::GEAR) = input_(IDX_U::GEAR); + delayed_input(IDX_U::SLOPE_ACCX) = input_(IDX_U::SLOPE_ACCX); + + const auto prev_state = state_; + + updateRungeKuttaWithController(dt, delayed_input); + + // take velocity/steer limit explicitly + state_(IDX::VX) = std::clamp(state_(IDX::VX), -vx_lim_, vx_lim_); + state_(IDX::STEER) = std::clamp(state_(IDX::STEER), -steer_lim_, steer_lim_); + + // consider gear + // update position and velocity first, and then acceleration is calculated naturally + updateStateWithGear(state_, prev_state, gear_, dt); +} + +void SimModelActuationCmdMechanical::updateRungeKuttaWithController( + const double dt, const Eigen::VectorXd & input) +{ + // 1) update longitudinal states + const Eigen::VectorXd k1_longitudinal = calcLongitudinalModel(state_, input); + const Eigen::VectorXd k2_longitudinal = + calcLongitudinalModel(state_ + k1_longitudinal * 0.5 * dt, input); + const Eigen::VectorXd k3_longitudinal = + calcLongitudinalModel(state_ + k2_longitudinal * 0.5 * dt, input); + const Eigen::VectorXd k4_longitudinal = + calcLongitudinalModel(state_ + k3_longitudinal * dt, input); + state_ += + dt / 6.0 * (k1_longitudinal + 2.0 * k2_longitudinal + 2.0 * k3_longitudinal + k4_longitudinal); + + // 2) update lateral states + const double steer = state_(IDX::STEER); + const double steer_des = input(IDX_U::STEER_DES); + const double vel = state_(IDX::VX); + + const double steer_tire_des = calculateSteeringTireCommand(vel, steer, steer_des); + + mechanical_controller_->set_steer(state_(IDX::STEER)); + const double new_steer = + mechanical_controller_->update_runge_kutta(steer_tire_des, vel, prev_steer_tire_des_, dt); + state_(IDX::STEER) = new_steer; + prev_steer_tire_des_ = steer_tire_des; +} + +void SimModelActuationCmdMechanical::setState(const Eigen::VectorXd & state) +{ + // NOTE: This function is intended to overwrite the state by setting the initial pose, etc. In + // that case, it is necessary to reset the pid and steering dynamics states of the mechanical + // controller. + mechanical_controller_->clear_state(); + mechanical_controller_->set_steer(state(IDX::STEER)); + state_ = state; +} /* ---------------------------------------- */ diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index d774617dc77f1..6f2590417e574 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -271,19 +271,11 @@ void declareVehicleInfoParams(rclcpp::NodeOptions & node_options) node_options.append_parameter_override("max_steer_angle", 0.7); } +// NOTE: +// command type and vehicle model type area common params to all vehicle models. +// currently, no vehicle model requires additional parameters. using DefaultParamType = std::tuple; -using ActuationCmdParamType = std::tuple; -using ParamType = std::variant; -std::unordered_map vehicle_model_type_map = { - {"IDEAL_STEER_VEL", typeid(DefaultParamType)}, - {"IDEAL_STEER_ACC", typeid(DefaultParamType)}, - {"IDEAL_STEER_ACC_GEARED", typeid(DefaultParamType)}, - {"DELAY_STEER_VEL", typeid(DefaultParamType)}, - {"DELAY_STEER_ACC", typeid(DefaultParamType)}, - {"DELAY_STEER_ACC_GEARED", typeid(DefaultParamType)}, - {"DELAY_STEER_ACC_GEARED_WO_FALL_GUARD", typeid(DefaultParamType)}, - {"ACTUATION_CMD", typeid(ActuationCmdParamType)}}; - +using ParamType = std::variant; std::pair get_common_params(const ParamType & params) { return std::visit( @@ -304,21 +296,10 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) rclcpp::init(0, nullptr); const auto params = GetParam(); - // common parameters const auto common_params = get_common_params(params); const auto command_type = common_params.first; const auto vehicle_model_type = common_params.second; - // optional parameters - std::optional conversion_type{}; // for ActuationCmdParamType - - // Determine the ParamType corresponding to vehicle_model_type and get the specific parameters. - const auto iter = vehicle_model_type_map.find(vehicle_model_type); - if (iter == vehicle_model_type_map.end()) { - throw std::invalid_argument("Unexpected vehicle_model_type."); - } - if (iter->second == typeid(ActuationCmdParamType)) { - conversion_type = std::get<2>(std::get(params)); - } + std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; rclcpp::NodeOptions node_options; node_options.append_parameter_override("initialize_source", "INITIAL_POSE_TOPIC"); @@ -331,7 +312,6 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) node_options.append_parameter_override("brake_time_constant", 0.2); node_options.append_parameter_override("convert_accel_cmd", true); node_options.append_parameter_override("convert_brake_cmd", true); - node_options.append_parameter_override("convert_steer_cmd", true); const auto share_dir = ament_index_cpp::get_package_share_directory("simple_planning_simulator"); const auto accel_map_path = share_dir + "/test/actuation_cmd_map/accel_map.csv"; const auto brake_map_path = share_dir + "/test/actuation_cmd_map/brake_map.csv"; @@ -342,17 +322,31 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) node_options.append_parameter_override("vgr_coef_a", 15.713); node_options.append_parameter_override("vgr_coef_b", 0.053); node_options.append_parameter_override("vgr_coef_c", 0.042); - if (conversion_type.has_value()) { - std::cout << "\n\n vehicle model = " << vehicle_model_type - << ", conversion_type = " << conversion_type.value() << std::endl - << std::endl; - node_options.append_parameter_override("convert_steer_cmd_method", conversion_type.value()); - } else { - std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; - } + // mechanical parameters + node_options.append_parameter_override("mechanical_params.kp", 386.915); + node_options.append_parameter_override("mechanical_params.ki", 5.461); + node_options.append_parameter_override("mechanical_params.kd", 0.036); + node_options.append_parameter_override("mechanical_params.ff_gain", 0.031); + node_options.append_parameter_override("mechanical_params.angle_limit", 10.0); + node_options.append_parameter_override("mechanical_params.rate_limit", 3.0); + node_options.append_parameter_override("mechanical_params.dead_zone_threshold", 0.007); + node_options.append_parameter_override("mechanical_params.poly_a", 0.153); + node_options.append_parameter_override("mechanical_params.poly_b", -0.173); + node_options.append_parameter_override("mechanical_params.poly_c", 1.590); + node_options.append_parameter_override("mechanical_params.poly_d", 0.002); + node_options.append_parameter_override("mechanical_params.poly_e", -0.042); + node_options.append_parameter_override("mechanical_params.poly_f", 0.184); + node_options.append_parameter_override("mechanical_params.poly_g", -0.063); + node_options.append_parameter_override("mechanical_params.poly_h", 0.187); + node_options.append_parameter_override("mechanical_params.inertia", 25.178); + node_options.append_parameter_override("mechanical_params.damping", 117.007); + node_options.append_parameter_override("mechanical_params.stiffness", 0.175); + node_options.append_parameter_override("mechanical_params.friction", 0.660); + node_options.append_parameter_override("mechanical_params.steering_torque_limit", 30.0); + node_options.append_parameter_override("mechanical_params.torque_delay_time", 0.001); declareVehicleInfoParams(node_options); - const auto sim_node = std::make_shared(node_options); + auto sim_node = std::make_shared(node_options); const auto pub_sub_node = std::make_shared(); @@ -364,7 +358,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) // acceleration or braking, and whether it turns left or right, and generate an actuation // command. So do not change the map. If it is necessary, you need to change this parameters as // well. - const double target_steer_actuation = 10.0f; + const double target_steer_actuation = 20.0f; const double target_accel_actuation = 0.5f; // const double target_brake_actuation = 0.5f; // unused for now. @@ -375,10 +369,15 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) const auto t = sim_node->now(); sendCommand(command_type, sim_node, pub_sub_node, t, ackermann_cmd, actuation_cmd); }; + // NOTE: Since the node has a queue, the node needs to be re-created. + auto _restartNode = [&]() { + sim_node.reset(); + sim_node = std::make_shared(node_options); + }; // check pub-sub connections { - size_t expected = 1; + constexpr size_t expected = 1; // actuation or ackermann must be subscribed const auto sub_command_count = (command_type == CommandType::Actuation) @@ -404,6 +403,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) // go backward // NOTE: positive acceleration with reverse gear drives the vehicle backward. + _restartNode(); _resetInitialpose(); _sendBwdGear(); _sendCommand( @@ -412,6 +412,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) isOnBackward(*(pub_sub_node->current_odom_), init_state); // go forward left + _restartNode(); _resetInitialpose(); _sendFwdGear(); _sendCommand( @@ -421,6 +422,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) // go backward right // NOTE: positive acceleration with reverse gear drives the vehicle backward. + _restartNode(); _resetInitialpose(); _sendBwdGear(); _sendCommand( @@ -443,5 +445,9 @@ INSTANTIATE_TEST_SUITE_P( std::make_tuple(CommandType::Ackermann, "DELAY_STEER_ACC_GEARED"), std::make_tuple(CommandType::Ackermann, "DELAY_STEER_ACC_GEARED_WO_FALL_GUARD"), /* Actuation type */ - std::make_tuple(CommandType::Actuation, "ACTUATION_CMD", "steer_map"), - std::make_tuple(CommandType::Actuation, "ACTUATION_CMD", "vgr"))); + // NOTE: Just "ACTUATION_CMD" sim model converts only accel/brake actuation commands. The test + // is performed for models that convert all accel/brake/steer commands, so the test for + // accel/brake alone is skipped. + std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_STEER_MAP"), + std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_VGR"), + std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_MECHANICAL"))); From 51098ebc48171f81393e53327dd26e9d422cb220 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 21:06:14 +0900 Subject: [PATCH 075/273] fix(autoware_behavior_path_start_planner_module): fix clang-diagnostic-unused-variable (#9405) fix: clang-diagnostic-unused-variable Signed-off-by: kobayu858 --- .../src/pull_out_planner_base.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp index e82db8a68740e..f7713ea2e91b2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/pull_out_planner_base.cpp @@ -26,7 +26,6 @@ bool PullOutPlannerBase::isPullOutPathCollided( const auto & dynamic_objects = planner_data_->dynamic_object; const auto pull_out_lanes = start_planner_utils::getPullOutLanes( planner_data_, planner_data_->parameters.backward_path_length + parameters_.max_back_distance); - const auto & vehicle_footprint = vehicle_info_.createFootprint(); // extract stop objects in pull out lane for collision check const auto stop_objects = utils::path_safety_checker::filterObjectsByVelocity( *dynamic_objects, parameters_.th_moving_object_velocity); From 6c20d58a5da8cb9feb6563e3101cb798ba2e56af Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 20 Nov 2024 21:06:29 +0900 Subject: [PATCH 076/273] fix(autoware_behavior_velocity_blind_spot_module): fix clang-diagnostic-unused-parameter (#9406) fix: clang-diagnostic-unused-parameter Signed-off-by: kobayu858 --- .../src/decisions.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp index da4582dd1643f..116050871c722 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp @@ -24,7 +24,7 @@ namespace autoware::behavior_velocity_planner */ template void BlindSpotModule::setRTCStatusByDecision( - const T &, const tier4_planning_msgs::msg::PathWithLaneId & path) + const T &, [[maybe_unused]] const tier4_planning_msgs::msg::PathWithLaneId & path) { static_assert("Unsupported type passed to setRTCStatus"); return; From d8087f40fdab6d8e289f3374b621aa5228a1e45a Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 20 Nov 2024 23:51:32 +0900 Subject: [PATCH 077/273] feat(pid_longitudinal_controller): suppress rclcpp_warning/error (#9384) * feat(pid_longitudinal_controller): suppress rclcpp_warning/error Signed-off-by: Takayuki Murooka * update codeowner Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../CMakeLists.txt | 2 + .../pid_longitudinal_controller.hpp | 13 ++++ .../package.xml | 1 + .../src/pid_longitudinal_controller.cpp | 71 +++++++++++-------- 4 files changed, 56 insertions(+), 31 deletions(-) diff --git a/control/autoware_pid_longitudinal_controller/CMakeLists.txt b/control/autoware_pid_longitudinal_controller/CMakeLists.txt index 4edba06ccee87..d0fef75a1154d 100644 --- a/control/autoware_pid_longitudinal_controller/CMakeLists.txt +++ b/control/autoware_pid_longitudinal_controller/CMakeLists.txt @@ -4,6 +4,8 @@ project(autoware_pid_longitudinal_controller) find_package(autoware_cmake REQUIRED) autoware_package() +find_package(fmt REQUIRED) + set(PID_LON_CON_LIB ${PROJECT_NAME}_lib) ament_auto_add_library(${PID_LON_CON_LIB} SHARED DIRECTORY src diff --git a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp index 1d4192d51d98d..7daf3013bab4a 100644 --- a/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp +++ b/control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp @@ -254,6 +254,12 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro void setupDiagnosticUpdater(); void checkControlState(diagnostic_updater::DiagnosticStatusWrapper & stat); + struct ResultWithReason + { + bool result{false}; + std::string reason{""}; + }; + /** * @brief set current and previous velocity with received message * @param [in] msg current state message @@ -298,6 +304,13 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro */ Motion calcEmergencyCtrlCmd(const double dt); + /** + * @brief change control state + * @param [in] new state + * @param [in] reason to change control state + */ + void changeControlState(const ControlState & control_state, const std::string & reason = ""); + /** * @brief update control state according to the current situation * @param [in] control_data control data diff --git a/control/autoware_pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml index 2e9ca5375932b..b4bf580e133e7 100644 --- a/control/autoware_pid_longitudinal_controller/package.xml +++ b/control/autoware_pid_longitudinal_controller/package.xml @@ -8,6 +8,7 @@ Takamasa Horibe Takayuki Murooka Mamoru Sobue + Yuki Takagi Apache 2.0 diff --git a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp index 9bc9a5cd59ac3..7f6da35527290 100644 --- a/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp +++ b/control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp @@ -18,6 +18,8 @@ #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/normalization.hpp" +#include + #include #include #include @@ -424,7 +426,8 @@ trajectory_follower::LongitudinalOutput PidLongitudinalController::run( // self pose is far from trajectory if (control_data.is_far_from_trajectory) { if (m_enable_large_tracking_error_emergency) { - m_control_state = ControlState::EMERGENCY; // update control state + // update control state + changeControlState(ControlState::EMERGENCY, "the tracking error is too large"); } const Motion raw_ctrl_cmd = calcEmergencyCtrlCmd(control_data.dt); // calculate control command m_prev_raw_ctrl_cmd = raw_ctrl_cmd; @@ -606,13 +609,23 @@ PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCm longitudinal_utils::applyDiffLimitFilter(raw_ctrl_cmd.acc, m_prev_raw_ctrl_cmd.acc, dt, p.jerk); m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, raw_ctrl_cmd.acc); - RCLCPP_ERROR_THROTTLE( - logger_, *clock_, 3000, "[Emergency stop] vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel, - raw_ctrl_cmd.acc); - return raw_ctrl_cmd; } +void PidLongitudinalController::changeControlState( + const ControlState & control_state, const std::string & reason) +{ + if (control_state != m_control_state) { + RCLCPP_DEBUG_STREAM( + logger_, + "controller state changed: " << toStr(m_control_state) << " -> " << toStr(control_state)); + if (control_state == ControlState::EMERGENCY) { + RCLCPP_ERROR(logger_, "Emergency Stop since %s", reason.c_str()); + } + } + m_control_state = control_state; +} + void PidLongitudinalController::updateControlState(const ControlData & control_data) { const double current_vel = control_data.current_motion.vel; @@ -662,19 +675,16 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d // ========================================================================================== const double current_vel_cmd = std::fabs( control_data.interpolated_traj.points.at(control_data.nearest_idx).longitudinal_velocity_mps); - const bool emergency_condition = m_enable_overshoot_emergency && - stop_dist < -p.emergency_state_overshoot_stop_dist && - current_vel_cmd < vel_epsilon; - const bool has_nonzero_target_vel = std::abs(current_vel_cmd) > 1.0e-5; - - const auto changeState = [this](const auto s) { - if (s != m_control_state) { - RCLCPP_DEBUG_STREAM( - logger_, "controller state changed: " << toStr(m_control_state) << " -> " << toStr(s)); + const auto emergency_condition = [&]() { + if ( + m_enable_overshoot_emergency && stop_dist < -p.emergency_state_overshoot_stop_dist && + current_vel_cmd < vel_epsilon) { + return ResultWithReason{ + true, fmt::format("the target velocity {} is less than {}", current_vel_cmd, vel_epsilon)}; } - m_control_state = s; - return; - }; + return ResultWithReason{false}; + }(); + const bool has_nonzero_target_vel = std::abs(current_vel_cmd) > 1.0e-5; const auto debug_msg_once = [this](const auto & s) { RCLCPP_DEBUG_ONCE(logger_, "%s", s); }; @@ -694,11 +704,11 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d // transit state // in DRIVE state if (m_control_state == ControlState::DRIVE) { - if (emergency_condition) { - return changeState(ControlState::EMERGENCY); + if (emergency_condition.result) { + return changeControlState(ControlState::EMERGENCY, emergency_condition.reason); } if (!is_under_control && stopped_condition) { - return changeState(ControlState::STOPPED); + return changeControlState(ControlState::STOPPED); } if (m_enable_smooth_stop) { @@ -709,11 +719,11 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d control_data.stop_dist - 0.5 * (pred_vel_in_target + current_vel) * m_delay_compensation_time; m_smooth_stop.init(pred_vel_in_target, pred_stop_dist); - return changeState(ControlState::STOPPING); + return changeControlState(ControlState::STOPPING); } } else { if (stopped_condition && !departure_condition_from_stopped) { - return changeState(ControlState::STOPPED); + return changeControlState(ControlState::STOPPED); } } return; @@ -721,11 +731,11 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d // in STOPPING state if (m_control_state == ControlState::STOPPING) { - if (emergency_condition) { - return changeState(ControlState::EMERGENCY); + if (emergency_condition.result) { + return changeControlState(ControlState::EMERGENCY, emergency_condition.reason); } if (stopped_condition) { - return changeState(ControlState::STOPPED); + return changeControlState(ControlState::STOPPED); } if (departure_condition_from_stopping) { @@ -733,7 +743,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d m_lpf_vel_error->reset(0.0); // prevent the car from taking a long time to start to move m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_raw_ctrl_cmd.acc); - return changeState(ControlState::DRIVE); + return changeControlState(ControlState::DRIVE); } return; } @@ -779,7 +789,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d m_pid_vel.reset(); m_lpf_vel_error->reset(0.0); m_lpf_acc_error->reset(0.0); - return changeState(ControlState::DRIVE); + return changeControlState(ControlState::DRIVE); } return; @@ -788,13 +798,13 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d // in EMERGENCY state if (m_control_state == ControlState::EMERGENCY) { if (stopped_condition) { - return changeState(ControlState::STOPPED); + return changeControlState(ControlState::STOPPED); } - if (!emergency_condition) { + if (!emergency_condition.result) { if (!is_under_control) { // NOTE: On manual driving, no need stopping to exit the emergency. - return changeState(ControlState::DRIVE); + return changeControlState(ControlState::DRIVE); } } return; @@ -1213,7 +1223,6 @@ void PidLongitudinalController::updateDebugVelAcc(const ControlData & control_da void PidLongitudinalController::setupDiagnosticUpdater() { - diag_updater_->setHardwareID("autoware_pid_longitudinal_controller"); diag_updater_->add("control_state", this, &PidLongitudinalController::checkControlState); } From 2f57890b691277de17e4465939b2c2a5527efaef Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Thu, 21 Nov 2024 10:03:03 +0900 Subject: [PATCH 078/273] fix(autoware_pointcloud_preprocessor): clang-tidy for overrides (#9414) fix: clang-tidy for overrides Signed-off-by: vividf --- .../crop_box_filter/crop_box_filter_node.hpp | 4 ++-- .../downsample_filter/voxel_grid_downsample_filter_node.hpp | 4 ++-- .../outlier_filter/ring_outlier_filter_node.hpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp index 7cc61798bfef9..2a983835e4e55 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp @@ -72,9 +72,9 @@ class CropBoxFilterComponent : public autoware::pointcloud_preprocessor::Filter // TODO(sykwer): Temporary Implementation: Remove this interface when all the filter nodes conform // to new API - virtual void faster_filter( + void faster_filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, - const TransformInfo & transform_info); + const TransformInfo & transform_info) override; void publishCropBoxPolygon(); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_node.hpp index a03b4a4cd0b86..7884890eb7d20 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/downsample_filter/voxel_grid_downsample_filter_node.hpp @@ -69,9 +69,9 @@ class VoxelGridDownsampleFilterComponent : public autoware::pointcloud_preproces // TODO(atsushi421): Temporary Implementation: Remove this interface when all the filter nodes // conform to new API - virtual void faster_filter( + void faster_filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, - const TransformInfo & transform_info); + const TransformInfo & transform_info) override; private: float voxel_size_x_; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp index b5aa9d56a0dfb..a19c0c1e257b2 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp @@ -49,9 +49,9 @@ class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Fil // TODO(sykwer): Temporary Implementation: Remove this interface when all the filter nodes conform // to new API - virtual void faster_filter( + void faster_filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, - const TransformInfo & transform_info); + const TransformInfo & transform_info) override; rclcpp::Publisher::SharedPtr visibility_pub_; From d17ffd3e87d1bf2d04e2a27fa6093dd79d7d43cb Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Thu, 21 Nov 2024 10:03:15 +0900 Subject: [PATCH 079/273] fix(autoware_pointcloud_preprocessor): clang-tidy error in distortion corrector (#9412) fix: clang-tidy Signed-off-by: vividf --- .../distortion_corrector/distortion_corrector.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp index d4432c24dd5b0..1cc8fd2ff407f 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp @@ -90,6 +90,9 @@ class DistortionCorrectorBase managed_tf_buffer_ = std::make_unique(&node, has_static_tf_only); } + + virtual ~DistortionCorrectorBase() = default; + [[nodiscard]] bool pointcloud_transform_exists() const; [[nodiscard]] bool pointcloud_transform_needed() const; std::deque get_twist_queue(); From 837138384275b6e004ab395f0a3f59d9d84cafe9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E3=81=90=E3=82=8B=E3=81=90=E3=82=8B?= Date: Thu, 21 Nov 2024 10:39:52 +0900 Subject: [PATCH 080/273] fix(evaluator): missing dependency in evaluator components (#9074) --- evaluator/autoware_planning_evaluator/package.xml | 1 + evaluator/kinematic_evaluator/package.xml | 1 + evaluator/localization_evaluator/package.xml | 1 + evaluator/perception_online_evaluator/package.xml | 1 + 4 files changed, 4 insertions(+) diff --git a/evaluator/autoware_planning_evaluator/package.xml b/evaluator/autoware_planning_evaluator/package.xml index 572c99d8ac3a5..15d5d6da8504d 100644 --- a/evaluator/autoware_planning_evaluator/package.xml +++ b/evaluator/autoware_planning_evaluator/package.xml @@ -30,6 +30,7 @@ tier4_metric_msgs ament_cmake_ros + ament_index_cpp ament_lint_auto autoware_lint_common diff --git a/evaluator/kinematic_evaluator/package.xml b/evaluator/kinematic_evaluator/package.xml index a70bf053171f3..99254d06d0642 100644 --- a/evaluator/kinematic_evaluator/package.xml +++ b/evaluator/kinematic_evaluator/package.xml @@ -29,6 +29,7 @@ tf2_ros ament_cmake_gtest + ament_index_cpp ament_lint_auto autoware_lint_common diff --git a/evaluator/localization_evaluator/package.xml b/evaluator/localization_evaluator/package.xml index f7c81fa101f30..49dd156f983b4 100644 --- a/evaluator/localization_evaluator/package.xml +++ b/evaluator/localization_evaluator/package.xml @@ -25,6 +25,7 @@ tf2_ros ament_cmake_gtest + ament_index_cpp ament_lint_auto autoware_lint_common diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/perception_online_evaluator/package.xml index 414f75253d5f0..654586a76453d 100644 --- a/evaluator/perception_online_evaluator/package.xml +++ b/evaluator/perception_online_evaluator/package.xml @@ -35,6 +35,7 @@ tf2_ros ament_cmake_ros + ament_index_cpp ament_lint_auto autoware_lint_common From 1c96aa61f94e4979c50ee80342c0eb6cb2cb5a91 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 21 Nov 2024 11:13:58 +0900 Subject: [PATCH 081/273] feat(build_depends.repos): change autoware_adapi_msgs version (#9420) Signed-off-by: Takagi, Isamu --- build_depends.repos | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build_depends.repos b/build_depends.repos index 0c1deb7194cfb..61a56463e2e41 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -28,7 +28,7 @@ repositories: core/autoware_adapi_msgs: type: git url: https://github.com/autowarefoundation/autoware_adapi_msgs.git - version: 1.3.0 + version: beta/1.7.0 core/autoware_internal_msgs: type: git url: https://github.com/autowarefoundation/autoware_internal_msgs.git From 03b696281037acaa01b960df3f38f95843516711 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 21 Nov 2024 13:41:42 +0900 Subject: [PATCH 082/273] fix(autoware_obstacle_cruise_planner): fix clang-diagnostic-delete-abstract-non-virtual-dtor (#9419) fix: clang-diagnostic-delete-abstract-non-virtual-dtor Signed-off-by: kobayu858 --- .../autoware/obstacle_cruise_planner/planner_interface.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp index df46f32610150..e4fb1c6cfe36d 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp @@ -42,6 +42,7 @@ using MetricArray = tier4_metric_msgs::msg::MetricArray; class PlannerInterface { public: + virtual ~PlannerInterface() = default; PlannerInterface( rclcpp::Node & node, const LongitudinalInfo & longitudinal_info, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, From f7f2fc07936dc5494b40756937c122a27a31706c Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 21 Nov 2024 13:41:56 +0900 Subject: [PATCH 083/273] fix(autoware_freespace_planning_algorithms): fix clang-diagnostic-ignored-optimization-argument (#9418) fix: clang-diagnostic-ignored-optimization-argument Signed-off-by: kobayu858 --- planning/autoware_freespace_planning_algorithms/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/autoware_freespace_planning_algorithms/CMakeLists.txt b/planning/autoware_freespace_planning_algorithms/CMakeLists.txt index 4f678cd9fdec5..5b6013528f7fc 100644 --- a/planning/autoware_freespace_planning_algorithms/CMakeLists.txt +++ b/planning/autoware_freespace_planning_algorithms/CMakeLists.txt @@ -60,6 +60,8 @@ find_package(Python3 REQUIRED COMPONENTS Interpreter Development) find_package(pybind11_vendor REQUIRED) find_package(pybind11 REQUIRED) +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-ignored-optimization-argument") + pybind11_add_module(${PROJECT_NAME}_pybind SHARED scripts/bind/astar_search_pybind.cpp ) From dd9c1162b0c097206b8ae3f05a16b2eddf537fbc Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 21 Nov 2024 13:42:10 +0900 Subject: [PATCH 084/273] fix(autoware_behavior_path_sampling_planner_module): fix clang-diagnostic-unused-variable (#9404) fix: clang-diagnostic-unused-variable Signed-off-by: kobayu858 --- .../sampling_planner_module.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp index e82c4fd287432..c9b75f7fa96de 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/include/autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp @@ -155,8 +155,6 @@ class SamplingPlannerModule : public SceneModuleInterface bool canTransitSuccessState() override { std::vector drivable_lanes{}; - const auto & prev_module_path = - std::make_shared(getPreviousModuleOutput().path); const auto prev_module_reference_path = std::make_shared(getPreviousModuleOutput().reference_path); From f070655c5d7c748cab553b0216bee9b81ba26b73 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara Date: Thu, 21 Nov 2024 16:03:15 +0900 Subject: [PATCH 085/273] feat(behavior_velocity_planner): update velocity factor initialization for run out module (#9352) feat(behavior_velocity_planner): update velocity factor initialization Update the initialization of the velocity factor in the RunOutModule of the behavior_velocity_planner. The velocity factor is now initialized for the RUN_OUT behavior instead of the ROUTE_OBSTACLE behavior. Signed-off-by: Kyoichi Sugahara --- .../autoware_behavior_velocity_run_out_module/src/scene.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index 2296655d700d3..c3f91d0506388 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -50,7 +50,7 @@ RunOutModule::RunOutModule( debug_ptr_(debug_ptr), state_machine_(std::make_unique(planner_param.approaching.state)) { - velocity_factor_.init(PlanningBehavior::ROUTE_OBSTACLE); + velocity_factor_.init(PlanningBehavior::RUN_OUT); if (planner_param.run_out.use_partition_lanelet) { const lanelet::LaneletMapConstPtr & ll = planner_data->route_handler_->getLaneletMapPtr(); From 0b7223943947e05c08378eda7e5c95c1ba6da7e1 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Thu, 21 Nov 2024 16:06:28 +0900 Subject: [PATCH 086/273] feat(obstacle_cruise_planner): outputs velocity factor when the ego follows front vehicle. (#9359) * feat(obstacle_cruise_planner): outputs velocity factor when the ego follows front vehicle. Signed-off-by: satoshi-ota * fix: cppcheck Signed-off-by: satoshi-ota --------- Signed-off-by: satoshi-ota --- .../obstacle_cruise_planner/utils.hpp | 4 +++ .../pid_based_planner/pid_based_planner.cpp | 4 +++ .../src/planner_interface.cpp | 29 +++++-------------- .../src/utils.cpp | 22 ++++++++++++++ 4 files changed, 37 insertions(+), 22 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp index 8af9a63f3a1fa..d929647d9bcd0 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp @@ -93,6 +93,10 @@ size_t getIndexWithLongitudinalOffset( } return 0; } + +VelocityFactorArray makeVelocityFactorArray( + const rclcpp::Time & time, const std::string & behavior = PlanningBehavior::ROUTE_OBSTACLE, + const std::optional pose = std::nullopt); } // namespace obstacle_cruise_utils #endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__UTILS_HPP_ diff --git a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp index 80fb85d4e30c9..da5d083d6ddcf 100644 --- a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp @@ -326,6 +326,10 @@ std::vector PIDBasedPlanner::planCruise( // cruise obstacle debug_data_ptr_->obstacles_to_cruise.push_back(cruise_obstacle_info->obstacle); debug_data_ptr_->cruise_metrics = makeMetrics("PIDBasedPlanner", "cruise", planner_data); + + velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray( + planner_data.current_time, PlanningBehavior::ADAPTIVE_CRUISE, + stop_traj_points.at(wall_idx).pose)); } // do cruise planning diff --git a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp index 140396a09e042..61946a8e4b37f 100644 --- a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp @@ -87,26 +87,6 @@ StopReasonArray makeEmptyStopReasonArray(const rclcpp::Time & current_time) return stop_reason_array; } -VelocityFactorArray makeVelocityFactorArray( - const rclcpp::Time & time, const std::optional pose = std::nullopt) -{ - VelocityFactorArray velocity_factor_array; - velocity_factor_array.header.frame_id = "map"; - velocity_factor_array.header.stamp = time; - - if (pose) { - using distance_type = VelocityFactor::_distance_type; - VelocityFactor velocity_factor; - velocity_factor.behavior = PlanningBehavior::ROUTE_OBSTACLE; - velocity_factor.pose = pose.value(); - velocity_factor.distance = std::numeric_limits::quiet_NaN(); - velocity_factor.status = VelocityFactor::UNKNOWN; - velocity_factor.detail = std::string(); - velocity_factor_array.factors.push_back(velocity_factor); - } - return velocity_factor_array; -} - double calcMinimumDistanceToStop( const double initial_vel, const double max_acc, const double min_acc) { @@ -247,7 +227,8 @@ std::vector PlannerInterface::generateStopTrajectory( if (stop_obstacles.empty()) { stop_reasons_pub_->publish(makeEmptyStopReasonArray(planner_data.current_time)); - velocity_factors_pub_->publish(makeVelocityFactorArray(planner_data.current_time)); + velocity_factors_pub_->publish( + obstacle_cruise_utils::makeVelocityFactorArray(planner_data.current_time)); // delete marker const auto markers = autoware::motion_utils::createDeletedStopVirtualWallMarker(planner_data.current_time, 0); @@ -403,7 +384,8 @@ std::vector PlannerInterface::generateStopTrajectory( const auto stop_reasons_msg = makeStopReasonArray(planner_data, stop_pose, *determined_stop_obstacle); stop_reasons_pub_->publish(stop_reasons_msg); - velocity_factors_pub_->publish(makeVelocityFactorArray(planner_data.current_time, stop_pose)); + velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray( + planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE, stop_pose)); // Store stop reason debug data debug_data_ptr_->stop_metrics = makeMetrics("PlannerInterface", "stop", planner_data, stop_pose, *determined_stop_obstacle); @@ -656,6 +638,9 @@ std::vector PlannerInterface::generateSlowDownTrajectory( const auto markers = autoware::motion_utils::createSlowDownVirtualWallMarker( slow_down_traj_points.at(slow_down_wall_idx).pose, "obstacle slow down", planner_data.current_time, i, abs_ego_offset, "", planner_data.is_driving_forward); + velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray( + planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE, + slow_down_traj_points.at(slow_down_wall_idx).pose)); autoware::universe_utils::appendMarkerArray(markers, &debug_data_ptr_->slow_down_wall_marker); } diff --git a/planning/autoware_obstacle_cruise_planner/src/utils.cpp b/planning/autoware_obstacle_cruise_planner/src/utils.cpp index bc52e800c8fc5..3bf6ee311ca13 100644 --- a/planning/autoware_obstacle_cruise_planner/src/utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/utils.cpp @@ -113,4 +113,26 @@ std::vector getClosestStopObstacles(const std::vector pose) +{ + VelocityFactorArray velocity_factor_array; + velocity_factor_array.header.frame_id = "map"; + velocity_factor_array.header.stamp = time; + + if (pose) { + using distance_type = VelocityFactor::_distance_type; + VelocityFactor velocity_factor; + velocity_factor.behavior = behavior; + velocity_factor.pose = pose.value(); + velocity_factor.distance = std::numeric_limits::quiet_NaN(); + velocity_factor.status = VelocityFactor::UNKNOWN; + velocity_factor.detail = std::string(); + velocity_factor_array.factors.push_back(velocity_factor); + } + return velocity_factor_array; +} + } // namespace obstacle_cruise_utils From 86070456b9e53bd7f4c86d8078e838511d4a28b8 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Thu, 21 Nov 2024 17:20:34 +0900 Subject: [PATCH 087/273] chore: update license of pointcloud preprocessor (#9397) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- sensing/autoware_pointcloud_preprocessor/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sensing/autoware_pointcloud_preprocessor/package.xml b/sensing/autoware_pointcloud_preprocessor/package.xml index 2fed0b54824be..85e42b4291626 100644 --- a/sensing/autoware_pointcloud_preprocessor/package.xml +++ b/sensing/autoware_pointcloud_preprocessor/package.xml @@ -15,6 +15,8 @@ David Wong Melike Tanrikulu Apache License 2.0 + + LGPLv3 Open Perception From 74ca3ab4128e19e01bdcddb46350b29376cfb566 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 21 Nov 2024 18:30:53 +0900 Subject: [PATCH 088/273] feat(goal_planner): do not insert shift end pose on pull over lane to path (#9361) Signed-off-by: kosuke55 --- .../src/pull_over_planner/shift_pull_over.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index f70dbbd9c1e50..c299957d16a66 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -206,9 +206,6 @@ std::optional ShiftPullOver::generatePullOverPath( shifted_path.path.points = autoware::motion_utils::removeOverlapPoints(shifted_path.path.points); autoware::motion_utils::insertOrientation(shifted_path.path.points, true); - // set same orientation, because the reference center line orientation is not same to the - shifted_path.path.points.back().point.pose.orientation = shift_end_pose.orientation; - // for debug. result of shift is not equal to the target const Pose actual_shift_end_pose = shifted_path.path.points.back().point.pose; From 60dbc46ae102a351d79f11a2c3748005e7ca0228 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 21 Nov 2024 19:51:35 +0900 Subject: [PATCH 089/273] refactor(goal_planner): rename shoulder_lane to pull_over_lane (#9422) Signed-off-by: kosuke55 --- .../pull_over_planner/shift_pull_over.hpp | 2 +- .../src/pull_over_planner/shift_pull_over.cpp | 8 +++---- .../geometric_parallel_parking.hpp | 8 +++---- .../geometric_parallel_parking.cpp | 22 +++++++++---------- 4 files changed, 20 insertions(+), 20 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp index bfb0173874784..08e0b8508c991 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp @@ -50,7 +50,7 @@ class ShiftPullOver : public PullOverPlannerBase const GoalCandidate & goal_candidate, const size_t id, const std::shared_ptr planner_data, const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, - const lanelet::ConstLanelets & shoulder_lanes, const double lateral_jerk) const; + const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const; static double calcBeforeShiftedArcLength( const PathWithLaneId & path, const double after_shifted_arc_length, const double dr); static std::vector splineTwoPoints( diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index c299957d16a66..e1184c49e40ba 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -132,7 +132,7 @@ std::optional ShiftPullOver::generatePullOverPath( const GoalCandidate & goal_candidate, const size_t id, const std::shared_ptr planner_data, const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes, - const lanelet::ConstLanelets & shoulder_lanes, const double lateral_jerk) const + const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const { const double pull_over_velocity = parameters_.pull_over_velocity; const double after_shift_straight_distance = parameters_.after_shift_straight_distance; @@ -224,7 +224,7 @@ std::optional ShiftPullOver::generatePullOverPath( p.point.longitudinal_velocity_mps = 0.0; p.point.pose = goal_pose; p.lane_ids = shifted_path.path.points.back().lane_ids; - for (const auto & lane : shoulder_lanes) { + for (const auto & lane : pull_over_lanes) { p.lane_ids.push_back(lane.id()); } shifted_path.path.points.push_back(p); @@ -246,7 +246,7 @@ std::optional ShiftPullOver::generatePullOverPath( } } // add shoulder lane_id if not found - for (const auto & lane : shoulder_lanes) { + for (const auto & lane : pull_over_lanes) { if ( std::find(point.lane_ids.begin(), point.lane_ids.end(), lane.id()) == point.lane_ids.end()) { @@ -294,7 +294,7 @@ std::optional ShiftPullOver::generatePullOverPath( }); const bool is_in_lanes = std::invoke([&]() -> bool { const auto drivable_lanes = - utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes); + utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes); const auto & dp = planner_data->drivable_area_expansion_parameters; const auto expanded_lanes = utils::expandLanelets( drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp index 518d1108f0ee1..9cc9bec8e963a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp @@ -70,11 +70,11 @@ class GeometricParallelParking bool isParking() const; bool planPullOver( const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes, - const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward, + const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward, const bool left_side_parking); bool planPullOut( const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes, - const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start, + const lanelet::ConstLanelets & pull_over_lanes, const bool left_side_start, const std::shared_ptr autoware_lane_departure_checker); void setParameters(const ParallelParkingParameters & parameters) { parameters_ = parameters; } @@ -117,7 +117,7 @@ class GeometricParallelParking void clearPaths(); std::vector planOneTrial( const Pose & start_pose, const Pose & goal_pose, const double R_E_far, - const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, + const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward, const bool left_side_parking, const double end_pose_offset, const double lane_departure_margin, const double arc_path_interval, const std::shared_ptr @@ -134,7 +134,7 @@ class GeometricParallelParking const bool left_side_parking); std::vector generatePullOverPaths( const Pose & start_pose, const Pose & goal_pose, const double R_E_far, - const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, + const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward, const bool left_side_parking, const double end_pose_offset, const double velocity); PathWithLaneId generateStraightPath( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp index e2218e37a771b..b18858e9dad04 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp @@ -105,7 +105,7 @@ void GeometricParallelParking::setVelocityToArcPaths( std::vector GeometricParallelParking::generatePullOverPaths( const Pose & start_pose, const Pose & goal_pose, const double R_E_far, - const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, + const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward, const bool left_side_parking, const double end_pose_offset, const double velocity) { @@ -115,7 +115,7 @@ std::vector GeometricParallelParking::generatePullOverPaths( const double arc_path_interval = is_forward ? parameters_.forward_parking_path_interval : parameters_.backward_parking_path_interval; auto arc_paths = planOneTrial( - start_pose, goal_pose, R_E_far, road_lanes, shoulder_lanes, is_forward, left_side_parking, + start_pose, goal_pose, R_E_far, road_lanes, pull_over_lanes, is_forward, left_side_parking, end_pose_offset, lane_departure_margin, arc_path_interval, {}); if (arc_paths.empty()) { return std::vector{}; @@ -156,7 +156,7 @@ void GeometricParallelParking::clearPaths() bool GeometricParallelParking::planPullOver( const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes, - const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward, + const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward, const bool left_side_parking) { const auto & common_params = planner_data_->parameters; @@ -186,7 +186,7 @@ bool GeometricParallelParking::planPullOver( } const auto paths = generatePullOverPaths( - *start_pose, goal_pose, R_E_far, road_lanes, shoulder_lanes, is_forward, left_side_parking, + *start_pose, goal_pose, R_E_far, road_lanes, pull_over_lanes, is_forward, left_side_parking, end_pose_offset, parameters_.forward_parking_velocity); if (!paths.empty()) { paths_ = paths; @@ -208,8 +208,8 @@ bool GeometricParallelParking::planPullOver( } const auto paths = generatePullOverPaths( - *start_pose, goal_pose, R_E_min_, road_lanes, shoulder_lanes, is_forward, left_side_parking, - end_pose_offset, parameters_.backward_parking_velocity); + *start_pose, goal_pose, R_E_min_, road_lanes, pull_over_lanes, is_forward, + left_side_parking, end_pose_offset, parameters_.backward_parking_velocity); if (!paths.empty()) { paths_ = paths; return true; @@ -222,7 +222,7 @@ bool GeometricParallelParking::planPullOver( bool GeometricParallelParking::planPullOut( const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes, - const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start, + const lanelet::ConstLanelets & pull_over_lanes, const bool left_side_start, const std::shared_ptr lane_departure_checker) { @@ -242,7 +242,7 @@ bool GeometricParallelParking::planPullOut( // plan reverse path of parking. end_pose <-> start_pose auto arc_paths = planOneTrial( - *end_pose, start_pose, R_E_min_, road_lanes, shoulder_lanes, is_forward, left_side_start, + *end_pose, start_pose, R_E_min_, road_lanes, pull_over_lanes, is_forward, left_side_start, start_pose_offset, parameters_.pull_out_lane_departure_margin, parameters_.pull_out_arc_path_interval, lane_departure_checker); if (arc_paths.empty()) { @@ -374,7 +374,7 @@ PathWithLaneId GeometricParallelParking::generateStraightPath( std::vector GeometricParallelParking::planOneTrial( const Pose & start_pose, const Pose & goal_pose, const double R_E_far, - const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes, + const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward, const bool left_side_parking, const double end_pose_offset, const double lane_departure_margin, const double arc_path_interval, const std::shared_ptr @@ -419,7 +419,7 @@ std::vector GeometricParallelParking::planOneTrial( } lanes.push_back(lane); } - lanes.insert(lanes.end(), shoulder_lanes.begin(), shoulder_lanes.end()); + lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); // If start_pose is parallel to goal_pose, we can know lateral deviation of edges of vehicle, // and detect lane departure. @@ -427,7 +427,7 @@ std::vector GeometricParallelParking::planOneTrial( const double R_front_near = std::hypot(R_E_far + common_params.vehicle_width / 2, common_params.base_link2front); const double distance_to_near_bound = - utils::getSignedDistanceFromBoundary(shoulder_lanes, arc_end_pose, left_side_parking); + utils::getSignedDistanceFromBoundary(pull_over_lanes, arc_end_pose, left_side_parking); const double near_deviation = R_front_near - R_E_far; if (std::abs(distance_to_near_bound) - near_deviation < lane_departure_margin) { return std::vector{}; From 248bba7f2a3cd6a8d0777350c6dce062e79f5967 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Thu, 21 Nov 2024 16:41:54 +0100 Subject: [PATCH 090/273] refactor(traffic_light_recognition_marker_publisher): prefix package and namespace with autoware (#9305) Signed-off-by: Esteve Fernandez --- common/.pages | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 2 +- .../Readme.md | 0 ...affic_light_recognition_visualization_sample.png | Bin ...ic_light_recognition_marker_publisher.launch.xml | 2 +- .../package.xml | 4 ++-- .../traffic_light_recognition_marker_publisher.cpp | 0 .../traffic_light_recognition_marker_publisher.hpp | 0 9 files changed, 5 insertions(+), 5 deletions(-) rename common/{traffic_light_recognition_marker_publisher => autoware_traffic_light_recognition_marker_publisher}/CHANGELOG.rst (100%) rename common/{traffic_light_recognition_marker_publisher => autoware_traffic_light_recognition_marker_publisher}/CMakeLists.txt (86%) rename common/{traffic_light_recognition_marker_publisher => autoware_traffic_light_recognition_marker_publisher}/Readme.md (100%) rename common/{traffic_light_recognition_marker_publisher => autoware_traffic_light_recognition_marker_publisher}/images/traffic_light_recognition_visualization_sample.png (100%) rename common/{traffic_light_recognition_marker_publisher => autoware_traffic_light_recognition_marker_publisher}/launch/traffic_light_recognition_marker_publisher.launch.xml (62%) rename common/{traffic_light_recognition_marker_publisher => autoware_traffic_light_recognition_marker_publisher}/package.xml (86%) rename common/{traffic_light_recognition_marker_publisher => autoware_traffic_light_recognition_marker_publisher}/src/traffic_light_recognition_marker_publisher.cpp (100%) rename common/{traffic_light_recognition_marker_publisher => autoware_traffic_light_recognition_marker_publisher}/src/traffic_light_recognition_marker_publisher.hpp (100%) diff --git a/common/.pages b/common/.pages index 2ca956927b905..27ee85c30ea77 100644 --- a/common/.pages +++ b/common/.pages @@ -40,7 +40,7 @@ nav: - 'tier4_system_rviz_plugin': common/tier4_system_rviz_plugin - 'tier4_traffic_light_rviz_plugin': common/tier4_traffic_light_rviz_plugin - 'tier4_vehicle_rviz_plugin': common/tier4_vehicle_rviz_plugin - - 'traffic_light_recognition_marker_publisher': common/traffic_light_recognition_marker_publisher/Readme + - 'autoware_traffic_light_recognition_marker_publisher': common/autoware_traffic_light_recognition_marker_publisher/Readme - 'Node': - 'Goal Distance Calculator': common/autoware_goal_distance_calculator/Readme - 'Path Distance Calculator': common/autoware_path_distance_calculator/Readme diff --git a/common/traffic_light_recognition_marker_publisher/CHANGELOG.rst b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst similarity index 100% rename from common/traffic_light_recognition_marker_publisher/CHANGELOG.rst rename to common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst diff --git a/common/traffic_light_recognition_marker_publisher/CMakeLists.txt b/common/autoware_traffic_light_recognition_marker_publisher/CMakeLists.txt similarity index 86% rename from common/traffic_light_recognition_marker_publisher/CMakeLists.txt rename to common/autoware_traffic_light_recognition_marker_publisher/CMakeLists.txt index d028ab21475f7..281a6fc7dc802 100644 --- a/common/traffic_light_recognition_marker_publisher/CMakeLists.txt +++ b/common/autoware_traffic_light_recognition_marker_publisher/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(traffic_light_recognition_marker_publisher) +project(autoware_traffic_light_recognition_marker_publisher) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/common/traffic_light_recognition_marker_publisher/Readme.md b/common/autoware_traffic_light_recognition_marker_publisher/Readme.md similarity index 100% rename from common/traffic_light_recognition_marker_publisher/Readme.md rename to common/autoware_traffic_light_recognition_marker_publisher/Readme.md diff --git a/common/traffic_light_recognition_marker_publisher/images/traffic_light_recognition_visualization_sample.png b/common/autoware_traffic_light_recognition_marker_publisher/images/traffic_light_recognition_visualization_sample.png similarity index 100% rename from common/traffic_light_recognition_marker_publisher/images/traffic_light_recognition_visualization_sample.png rename to common/autoware_traffic_light_recognition_marker_publisher/images/traffic_light_recognition_visualization_sample.png diff --git a/common/traffic_light_recognition_marker_publisher/launch/traffic_light_recognition_marker_publisher.launch.xml b/common/autoware_traffic_light_recognition_marker_publisher/launch/traffic_light_recognition_marker_publisher.launch.xml similarity index 62% rename from common/traffic_light_recognition_marker_publisher/launch/traffic_light_recognition_marker_publisher.launch.xml rename to common/autoware_traffic_light_recognition_marker_publisher/launch/traffic_light_recognition_marker_publisher.launch.xml index b982be34e77d3..60f5c34e1f283 100644 --- a/common/traffic_light_recognition_marker_publisher/launch/traffic_light_recognition_marker_publisher.launch.xml +++ b/common/autoware_traffic_light_recognition_marker_publisher/launch/traffic_light_recognition_marker_publisher.launch.xml @@ -1,5 +1,5 @@ - + diff --git a/common/traffic_light_recognition_marker_publisher/package.xml b/common/autoware_traffic_light_recognition_marker_publisher/package.xml similarity index 86% rename from common/traffic_light_recognition_marker_publisher/package.xml rename to common/autoware_traffic_light_recognition_marker_publisher/package.xml index 8d3f422171611..88addcfb77b44 100644 --- a/common/traffic_light_recognition_marker_publisher/package.xml +++ b/common/autoware_traffic_light_recognition_marker_publisher/package.xml @@ -1,9 +1,9 @@ - traffic_light_recognition_marker_publisher + autoware_traffic_light_recognition_marker_publisher 0.38.0 - The traffic_light_recognition_marker_publisher package + The autoware_traffic_light_recognition_marker_publisher package Tomoya Kimura Takeshi Miura Shumpei Wakabayashi diff --git a/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp b/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp similarity index 100% rename from common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp rename to common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp diff --git a/common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp b/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp similarity index 100% rename from common/traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp rename to common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp From 3be9fd6621936681541c8dd2e07fd7519ea95013 Mon Sep 17 00:00:00 2001 From: Zhanhong Yan <43631587+Ericpotato@users.noreply.github.com> Date: Fri, 22 Nov 2024 15:46:18 +0900 Subject: [PATCH 091/273] fix(static_centerline_generator): map_tf_generator package name needs update (#9383) fix map_tf_generator name in autoware_static_centerline_generator.launch Signed-off-by: Ericpotato --- .../launch/static_centerline_generator.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml index b897cf4d88711..7d97caf4b375f 100644 --- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -40,7 +40,7 @@ - + From 834ba991e120987236a1fd0ed68fe78ff04b082f Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 22 Nov 2024 15:51:29 +0900 Subject: [PATCH 092/273] chore(autoware_behavior_velocity_stop_line_module): add maintainer (#9427) Signed-off-by: Y.Hisaki --- .../autoware_behavior_velocity_stop_line_module/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml index 68a8d919512b1..e24f167eb2058 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml @@ -5,6 +5,8 @@ 0.38.0 The autoware_behavior_velocity_stop_line_module package + Yukinari Hisaki + Satoshi Ota Fumiya Watanabe Zhe Shen Tomoya Kimura From 328afb446e07dbf92fb616a267e4515948dd5121 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 22 Nov 2024 16:05:11 +0900 Subject: [PATCH 093/273] fix(goal_planner): use departure_check_lane for path (#9423) --- .../pull_over_planner/geometric_pull_over.cpp | 5 +++-- .../src/pull_over_planner/shift_pull_over.cpp | 18 ++++++------------ 2 files changed, 9 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp index 09be040019338..f75358601d877 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/geometric_pull_over.cpp @@ -55,7 +55,6 @@ std::optional GeometricPullOver::plan( if (road_lanes.empty() || pull_over_lanes.empty()) { return {}; } - const auto lanes = utils::combineLanelets(road_lanes, pull_over_lanes); const auto & p = parallel_parking_parameters_; const double max_steer_angle = @@ -69,10 +68,12 @@ std::optional GeometricPullOver::plan( return {}; } + const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet( + pull_over_lanes, *planner_data->route_handler, left_side_parking_); const auto arc_path = planner_.getArcPath(); // check lane departure with road and shoulder lanes - if (lane_departure_checker_.checkPathWillLeaveLane(lanes, arc_path)) return {}; + if (lane_departure_checker_.checkPathWillLeaveLane({departure_check_lane}, arc_path)) return {}; auto pull_over_path_opt = PullOverPath::create( getPlannerType(), id, planner_.getPaths(), planner_.getStartPose(), modified_goal_pose, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index e1184c49e40ba..da99c830c68bb 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -292,18 +292,12 @@ std::optional ShiftPullOver::generatePullOverPath( return is_footprint_in_any_polygon(footprint); }); }); - const bool is_in_lanes = std::invoke([&]() -> bool { - const auto drivable_lanes = - utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes); - const auto & dp = planner_data->drivable_area_expansion_parameters; - const auto expanded_lanes = utils::expandLanelets( - drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset, - dp.drivable_area_types_to_skip); - const auto combined_drivable = utils::combineDrivableLanes( - expanded_lanes, previous_module_output.drivable_area_info.drivable_lanes); - return !lane_departure_checker_.checkPathWillLeaveLane( - utils::transformToLanelets(combined_drivable), pull_over_path.parking_path()); - }); + + const auto departure_check_lane = goal_planner_utils::createDepartureCheckLanelet( + pull_over_lanes, *planner_data->route_handler, left_side_parking_); + const bool is_in_lanes = !lane_departure_checker_.checkPathWillLeaveLane( + {departure_check_lane}, pull_over_path.parking_path()); + if (!is_in_parking_lots && !is_in_lanes) { return {}; } From e5181a5630a8d0af9713112be82c31b1e3ba4821 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Fri, 22 Nov 2024 16:09:56 +0900 Subject: [PATCH 094/273] fix(autoware_ndt_scan_matcher): remove unsed functions (#9387) Signed-off-by: Ryuta Kambe --- .../ndt_omp/multi_voxel_grid_covariance_omp.h | 12 +-- .../ndt_omp/multigrid_ndt_omp.h | 74 ------------------- 2 files changed, 1 insertion(+), 85 deletions(-) diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h index 0e43b0b35aecd..35451ede3a6aa 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multi_voxel_grid_covariance_omp.h @@ -171,12 +171,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid return *this; } - /** \brief Get the voxel covariance. - * \return covariance matrix - */ - const Eigen::Matrix3d & getCov() const { return (cov_); } - Eigen::Matrix3d & getCov() { return (cov_); } - /** \brief Get the inverse of the voxel covariance. * \return inverse covariance matrix */ @@ -191,11 +185,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid Eigen::Vector3d & getMean() { return (mean_); } - /** \brief Get the number of points contained by this voxel. - * \return number of points - */ - int getPointCount() const { return (nr_points_); } - /** \brief Number of points contained by voxel */ int nr_points_; @@ -352,6 +341,7 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid } // A wrapper of the real apply_filter + // cppcheck-suppress unusedFunction inline bool apply_filter_thread(int tid, GridNodeType & node) { apply_filter(processing_inputs_[tid], node); diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h index b173d164de97d..00c567775a6bf 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h @@ -132,15 +132,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration calculateNearestVoxelScoreEachPoint( const PointCloudSource & cloud) const; - inline void setRegularizationScaleFactor(float regularization_scale_factor) - { - params_.regularization_scale_factor = regularization_scale_factor; - } - inline void setRegularizationPose(Eigen::Matrix4f regularization_pose) { regularization_pose_ = regularization_pose; @@ -298,29 +247,6 @@ class MultiGridNormalDistributionsTransform : public pcl::Registration Date: Fri, 22 Nov 2024 16:30:22 +0900 Subject: [PATCH 095/273] refactor(lane_change): separate target lane leading based on obj behavior (#9372) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * separate target lane leading objects based on behavior (RT1-8532) Signed-off-by: Zulfaqar Azmi * fixed overlapped filtering and lanes debug marker Signed-off-by: Zulfaqar Azmi * combine filteredObjects function Signed-off-by: Zulfaqar Azmi * renaming functions and type Signed-off-by: Zulfaqar Azmi * update some logic to check is stopped Signed-off-by: Zulfaqar Azmi * rename expanded to stopped_outside_boundary Signed-off-by: Zulfaqar Azmi * Include docstring Signed-off-by: Zulfaqar Azmi * rename stopped_outside_boundary → stopped_at_bound Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> Signed-off-by: Zulfaqar Azmi * spell-check Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> --- .../scene.hpp | 7 +- .../utils/base_class.hpp | 2 +- .../utils/data_structs.hpp | 34 ++- .../utils/debug_structs.hpp | 8 +- .../utils/markers.hpp | 4 +- .../utils/utils.hpp | 46 ++- .../package.xml | 1 + .../src/scene.cpp | 275 ++++++------------ .../src/utils/markers.cpp | 52 ++-- .../src/utils/utils.cpp | 139 +++++---- .../path_safety_checker/objects_filtering.hpp | 5 +- .../path_safety_checker/objects_filtering.cpp | 9 +- .../test/test_objects_filtering.cpp | 15 +- 13 files changed, 284 insertions(+), 313 deletions(-) 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 dd21233c716f1..550925c4a10fc 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 @@ -121,16 +121,13 @@ class NormalLaneChange : public LaneChangeBase TurnSignalInfo get_terminal_turn_signal_info() const final; lane_change::TargetObjects get_target_objects( - const FilteredByLanesExtendedObjects & filtered_objects, + const FilteredLanesObjects & filtered_objects, const lanelet::ConstLanelets & current_lanes) const; - FilteredByLanesExtendedObjects filterObjects() const; + FilteredLanesObjects filter_objects() const; void filterOncomingObjects(PredictedObjects & objects) const; - FilteredByLanesObjects filterObjectsByLanelets( - const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path) const; - bool get_prepare_segment( PathWithLaneId & prepare_segment, const double prepare_length) const override; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index 634f3b737942b..e5c7fcb6d621e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -276,7 +276,7 @@ class LaneChangeBase std::shared_ptr abort_path_{}; std::shared_ptr planner_data_{}; lane_change::CommonDataPtr common_data_ptr_{}; - FilteredByLanesExtendedObjects filtered_objects_{}; + FilteredLanesObjects filtered_objects_{}; BehaviorModuleOutput prev_module_output_{}; std::optional lane_change_stop_pose_{std::nullopt}; 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 16b2b69a81af8..231353e812dd1 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 @@ -262,25 +262,28 @@ struct Info } }; -template -struct LanesObjects +struct TargetLaneLeadingObjects { - Object current_lane{}; - Object target_lane_leading{}; - Object target_lane_trailing{}; - Object other_lane{}; - - LanesObjects() = default; - LanesObjects( - Object current_lane, Object target_lane_leading, Object target_lane_trailing, Object other_lane) - : current_lane(std::move(current_lane)), - target_lane_leading(std::move(target_lane_leading)), - target_lane_trailing(std::move(target_lane_trailing)), - other_lane(std::move(other_lane)) + ExtendedPredictedObjects moving; + ExtendedPredictedObjects stopped; + + // for objects outside of target lanes, but close to its boundaries + ExtendedPredictedObjects stopped_at_bound; + + [[nodiscard]] size_t size() const { + return moving.size() + stopped.size() + stopped_at_bound.size(); } }; +struct FilteredLanesObjects +{ + ExtendedPredictedObjects others; + ExtendedPredictedObjects current_lane; + ExtendedPredictedObjects target_lane_trailing; + TargetLaneLeadingObjects target_lane_leading; +}; + struct TargetObjects { ExtendedPredictedObjects leading; @@ -418,8 +421,7 @@ using LaneChangeStates = lane_change::States; using LaneChangePhaseInfo = lane_change::PhaseInfo; using LaneChangePhaseMetrics = lane_change::PhaseMetrics; using LaneChangeInfo = lane_change::Info; -using FilteredByLanesObjects = lane_change::LanesObjects>; -using FilteredByLanesExtendedObjects = lane_change::LanesObjects; +using FilteredLanesObjects = lane_change::FilteredLanesObjects; using LateralAccelerationMap = lane_change::LateralAccelerationMap; } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp index fc51a82a8a842..a28b8523a75c7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/debug_structs.hpp @@ -35,7 +35,7 @@ struct Debug LaneChangePaths valid_paths; CollisionCheckDebugMap collision_check_objects; CollisionCheckDebugMap collision_check_objects_after_approval; - FilteredByLanesExtendedObjects filtered_objects; + FilteredLanesObjects filtered_objects; geometry_msgs::msg::Polygon execution_area; geometry_msgs::msg::Pose ego_pose; lanelet::ConstLanelets current_lanes; @@ -55,9 +55,11 @@ struct Debug collision_check_objects.clear(); collision_check_objects_after_approval.clear(); filtered_objects.current_lane.clear(); - filtered_objects.target_lane_leading.clear(); filtered_objects.target_lane_trailing.clear(); - filtered_objects.other_lane.clear(); + filtered_objects.target_lane_leading.moving.clear(); + filtered_objects.target_lane_leading.stopped.clear(); + filtered_objects.target_lane_leading.stopped_at_bound.clear(); + filtered_objects.others.clear(); execution_area.points.clear(); current_lanes.clear(); target_lanes.clear(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp index d403e7e1436c7..c95b388a2e4a4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/markers.hpp @@ -29,7 +29,7 @@ namespace marker_utils::lane_change_markers { -using autoware::behavior_path_planner::FilteredByLanesExtendedObjects; +using autoware::behavior_path_planner::FilteredLanesObjects; using autoware::behavior_path_planner::LaneChangePath; using autoware::behavior_path_planner::lane_change::Debug; using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects; @@ -40,7 +40,7 @@ MarkerArray createLaneChangingVirtualWallMarker( const geometry_msgs::msg::Pose & lane_changing_pose, const std::string & module_name, const rclcpp::Time & now, const std::string & ns); MarkerArray showFilteredObjects( - const FilteredByLanesExtendedObjects & filtered_objects, const std::string & ns); + const FilteredLanesObjects & filtered_objects, const std::string & ns); MarkerArray createExecutionArea(const geometry_msgs::msg::Polygon & execution_area); MarkerArray showExecutionInfo(const Debug & debug_data, const geometry_msgs::msg::Pose & ego_pose); MarkerArray createDebugMarkerArray( 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 edf64ecdc49ee..a02a61d5e72b6 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 @@ -54,6 +54,7 @@ using behavior_path_planner::lane_change::CommonDataPtr; using behavior_path_planner::lane_change::LanesPolygon; using behavior_path_planner::lane_change::ModuleType; using behavior_path_planner::lane_change::PathSafetyStatus; +using behavior_path_planner::lane_change::TargetLaneLeadingObjects; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; @@ -144,8 +145,7 @@ lanelet::BasicPolygon2d create_polygon( const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist); ExtendedPredictedObject transform( - const PredictedObject & object, const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters); + const PredictedObject & object, const LaneChangeParameters & lane_change_parameters); bool is_collided_polygons_in_lanelet( const std::vector & collided_polygons, const lanelet::BasicPolygon2d & lanes_polygon); @@ -240,17 +240,14 @@ bool is_same_lane_with_prev_iteration( bool is_ahead_of_ego( const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, - const PredictedObject & object); + const ExtendedPredictedObject & object); bool is_before_terminal( const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, - const PredictedObject & object); + const ExtendedPredictedObject & object); double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, const Pose & pose); -ExtendedPredictedObjects transform_to_extended_objects( - const CommonDataPtr & common_data_ptr, const std::vector & objects); - double get_distance_to_next_regulatory_element( const CommonDataPtr & common_data_ptr, const bool ignore_crosswalk = false, const bool ignore_intersection = false); @@ -274,7 +271,7 @@ double get_distance_to_next_regulatory_element( * found, returns the maximum possible double value. */ double get_min_dist_to_current_lanes_obj( - const CommonDataPtr & common_data_ptr, const FilteredByLanesExtendedObjects & filtered_objects, + const CommonDataPtr & common_data_ptr, const FilteredLanesObjects & filtered_objects, const double dist_to_target_lane_start, const PathWithLaneId & path); /** @@ -294,8 +291,8 @@ double get_min_dist_to_current_lanes_obj( * otherwise, false. */ bool has_blocking_target_object( - const CommonDataPtr & common_data_ptr, const FilteredByLanesExtendedObjects & filtered_objects, - const double stop_arc_length, const PathWithLaneId & path); + const TargetLaneLeadingObjects & target_leading_objects, const double stop_arc_length, + const PathWithLaneId & path); /** * @brief Checks if the ego vehicle has passed any turn direction within an intersection. @@ -342,5 +339,34 @@ std::vector get_line_string_paths(const ExtendedPredictedObject & */ bool has_overtaking_turn_lane_object( const CommonDataPtr & common_data_ptr, const ExtendedPredictedObjects & trailing_objects); + +/** + * @brief Filters objects based on their positions and velocities relative to the ego vehicle and + * the target lane. + * + * This function evaluates whether an object should be classified as a leading or trailing object + * in the context of a lane change. Objects are filtered based on their lateral distance from + * the ego vehicle, velocity, and whether they are within the target lane or its expanded + * boundaries. + * + * @param common_data_ptr Shared pointer to CommonData containing information about current lanes, + * vehicle dimensions, lane polygons, and behavior parameters. + * @param object An extended predicted object representing a potential obstacle in the environment. + * @param dist_ego_to_current_lanes_center Distance from the ego vehicle to the center of the + * current lanes. + * @param ahead_of_ego Boolean flag indicating if the object is ahead of the ego vehicle. + * @param before_terminal Boolean flag indicating if the ego vehicle is before the terminal point of + * the lane. + * @param leading_objects Reference to a structure for storing leading objects (stopped, moving, or + * outside boundaries). + * @param trailing_objects Reference to a collection for storing trailing objects. + * + * @return true if the object is classified as either leading or trailing, false otherwise. + */ +bool filter_target_lane_objects( + const CommonDataPtr & common_data_ptr, const ExtendedPredictedObject & object, + const double dist_ego_to_current_lanes_center, const bool ahead_of_ego, + const bool before_terminal, TargetLaneLeadingObjects & leading_objects, + ExtendedPredictedObjects & trailing_objects); } // namespace autoware::behavior_path_planner::utils::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ 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 a755b8dc0d42b..aef3d357c20da 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 @@ -27,6 +27,7 @@ autoware_rtc_interface autoware_universe_utils pluginlib + range-v3 rclcpp tier4_planning_msgs visualization_msgs 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 3f06ff0481c7e..942902b836c95 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 @@ -30,6 +30,10 @@ #include #include #include +#include +#include +#include +#include #include #include @@ -45,8 +49,8 @@ namespace autoware::behavior_path_planner { using autoware::motion_utils::calcSignedArcLength; using utils::lane_change::create_lanes_polygon; -using utils::path_safety_checker::isPolygonOverlapLanelet; namespace calculation = utils::lane_change::calculation; +using utils::path_safety_checker::filter::velocity_filter; NormalLaneChange::NormalLaneChange( const std::shared_ptr & parameters, LaneChangeModuleType type, @@ -111,6 +115,18 @@ void NormalLaneChange::update_lanes(const bool is_approved) *route_handler_ptr, get_target_lanes(), common_data_ptr_->get_ego_pose(), common_data_ptr_->lc_param_ptr->backward_lane_length); + lane_change_debug_.current_lanes = common_data_ptr_->lanes_ptr->current; + lane_change_debug_.target_lanes = common_data_ptr_->lanes_ptr->target; + + lane_change_debug_.target_backward_lanes.clear(); + ranges::for_each( + common_data_ptr_->lanes_ptr->preceding_target, + [&](const lanelet::ConstLanelets & preceding_lanes) { + ranges::insert( + lane_change_debug_.target_backward_lanes, lane_change_debug_.target_backward_lanes.end(), + preceding_lanes); + }); + *common_data_ptr_->lanes_polygon_ptr = create_lanes_polygon(common_data_ptr_); } @@ -193,7 +209,7 @@ void NormalLaneChange::update_transient_data() void NormalLaneChange::update_filtered_objects() { - filtered_objects_ = filterObjects(); + filtered_objects_ = filter_objects(); } void NormalLaneChange::updateLaneChangeStatus() @@ -566,7 +582,7 @@ void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path) // [ego]> | <--- stop margin ---> [obj]> // ---------------------------------------------------------- const auto has_blocking_target_lane_obj = utils::lane_change::has_blocking_target_object( - common_data_ptr_, filtered_objects_, stop_arc_length_behind_obj, path); + filtered_objects_.target_lane_leading, stop_arc_length_behind_obj, path); if (has_blocking_target_lane_obj || stop_arc_length_behind_obj <= 0.0) { set_stop_pose(dist_to_terminal_stop, path); @@ -926,30 +942,31 @@ bool NormalLaneChange::get_prepare_segment( } lane_change::TargetObjects NormalLaneChange::get_target_objects( - const FilteredByLanesExtendedObjects & filtered_objects, + const FilteredLanesObjects & filtered_objects, [[maybe_unused]] const lanelet::ConstLanelets & current_lanes) const { - ExtendedPredictedObjects leading_objects = filtered_objects.target_lane_leading; + ExtendedPredictedObjects leading_objects = filtered_objects.target_lane_leading.moving; + auto insert_leading_objects = [&](const auto & objects) { + ranges::actions::insert(leading_objects, leading_objects.end(), objects); + }; + + insert_leading_objects(filtered_objects.target_lane_leading.stopped); + insert_leading_objects(filtered_objects.target_lane_leading.stopped_at_bound); const auto chk_obj_in_curr_lanes = lane_change_parameters_->check_objects_on_current_lanes; if (chk_obj_in_curr_lanes || common_data_ptr_->transient_data.is_ego_stuck) { - leading_objects.insert( - leading_objects.end(), filtered_objects.current_lane.begin(), - filtered_objects.current_lane.end()); + insert_leading_objects(filtered_objects.current_lane); } const auto chk_obj_in_other_lanes = lane_change_parameters_->check_objects_on_other_lanes; if (chk_obj_in_other_lanes) { - leading_objects.insert( - leading_objects.end(), filtered_objects.other_lane.begin(), - filtered_objects.other_lane.end()); + insert_leading_objects(filtered_objects.others); } return {leading_objects, filtered_objects.target_lane_trailing}; } -FilteredByLanesExtendedObjects NormalLaneChange::filterObjects() const +FilteredLanesObjects NormalLaneChange::filter_objects() const { - const auto & route_handler = getRouteHandler(); auto objects = *planner_data_->dynamic_object; utils::path_safety_checker::filterObjectsByClass( objects, lane_change_parameters_->object_types_to_check); @@ -964,64 +981,81 @@ FilteredByLanesExtendedObjects NormalLaneChange::filterObjects() const return {}; } - const auto & current_lanes = get_current_lanes(); - - if (current_lanes.empty()) { + if (!common_data_ptr_->is_lanes_available()) { return {}; } - const auto & target_lanes = get_target_lanes(); + const auto & current_pose = common_data_ptr_->get_ego_pose(); + const auto & current_lanes = common_data_ptr_->lanes_ptr->current; - if (target_lanes.empty()) { - return {}; - } + const auto & current_lanes_ref_path = common_data_ptr_->current_lanes_path; - const auto & path = common_data_ptr_->current_lanes_path; + const auto & lanes_polygon = *common_data_ptr_->lanes_polygon_ptr; + const auto dist_ego_to_current_lanes_center = + lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); - auto filtered_by_lanes_objects = filterObjectsByLanelets(objects, path); + FilteredLanesObjects filtered_objects; + const auto reserve_size = objects.objects.size(); + filtered_objects.current_lane.reserve(reserve_size); + auto & target_lane_leading = filtered_objects.target_lane_leading; + target_lane_leading.stopped.reserve(reserve_size); + target_lane_leading.moving.reserve(reserve_size); + target_lane_leading.stopped_at_bound.reserve(reserve_size); + filtered_objects.target_lane_trailing.reserve(reserve_size); + filtered_objects.others.reserve(reserve_size); - const auto is_within_vel_th = [](const auto & object) -> bool { - constexpr double min_vel_th = 1.0; - constexpr double max_vel_th = std::numeric_limits::max(); - return utils::path_safety_checker::filter::velocity_filter(object, min_vel_th, max_vel_th); - }; + const auto stopped_obj_vel_th = common_data_ptr_->lc_param_ptr->stopped_object_velocity_threshold; - utils::path_safety_checker::filterObjects( - filtered_by_lanes_objects.target_lane_trailing, - [&](const PredictedObject & object) { return is_within_vel_th(object); }); + for (const auto & object : objects.objects) { + auto ext_object = utils::lane_change::transform(object, *common_data_ptr_->lc_param_ptr); + const auto & ext_obj_pose = ext_object.initial_pose; + ext_object.dist_from_ego = autoware::motion_utils::calcSignedArcLength( + current_lanes_ref_path.points, current_pose.position, ext_obj_pose.position); - if (lane_change_parameters_->check_objects_on_other_lanes) { - utils::path_safety_checker::filterObjects( - filtered_by_lanes_objects.other_lane, [&](const PredictedObject & object) { - const auto ahead_of_ego = - utils::lane_change::is_ahead_of_ego(common_data_ptr_, path, object); - return is_within_vel_th(object) && ahead_of_ego; - }); + const auto is_before_terminal = + utils::lane_change::is_before_terminal(common_data_ptr_, current_lanes_ref_path, ext_object); + + const auto ahead_of_ego = + utils::lane_change::is_ahead_of_ego(common_data_ptr_, current_lanes_ref_path, ext_object); + + if (utils::lane_change::filter_target_lane_objects( + common_data_ptr_, ext_object, dist_ego_to_current_lanes_center, ahead_of_ego, + is_before_terminal, target_lane_leading, filtered_objects.target_lane_trailing)) { + continue; + } + + // TODO(Azu): We have to think about how to remove is_within_vel_th without breaking AW behavior + const auto is_moving = velocity_filter( + ext_object.initial_twist, stopped_obj_vel_th, std::numeric_limits::max()); + + if ( + ahead_of_ego && is_moving && is_before_terminal && + !boost::geometry::disjoint(ext_object.initial_polygon, lanes_polygon.current)) { + // check only the objects that are in front of the ego vehicle + filtered_objects.current_lane.push_back(ext_object); + continue; + } + + filtered_objects.others.push_back(ext_object); } - // TODO(Azu): We have to think about how to remove is_within_vel_th without breaking AW behavior - utils::path_safety_checker::filterObjects( - filtered_by_lanes_objects.current_lane, [&](const PredictedObject & object) { - const auto ahead_of_ego = utils::lane_change::is_ahead_of_ego(common_data_ptr_, path, object); - return is_within_vel_th(object) && ahead_of_ego; - }); + const auto dist_comparator = [](const auto & obj1, const auto & obj2) { + return obj1.dist_from_ego < obj2.dist_from_ego; + }; + + // There are no use cases for other lane objects yet, so to save some computation time, we dont + // have to sort them. + ranges::sort(filtered_objects.current_lane, dist_comparator); + ranges::sort(target_lane_leading.stopped_at_bound, dist_comparator); + ranges::sort(target_lane_leading.stopped, dist_comparator); + ranges::sort(target_lane_leading.moving, dist_comparator); + ranges::sort(filtered_objects.target_lane_trailing, [&](const auto & obj1, const auto & obj2) { + return !dist_comparator(obj1, obj2); + }); + + lane_change_debug_.filtered_objects = filtered_objects; - const auto target_lane_leading_extended_objects = - utils::lane_change::transform_to_extended_objects( - common_data_ptr_, filtered_by_lanes_objects.target_lane_leading); - const auto target_lane_trailing_extended_objects = - utils::lane_change::transform_to_extended_objects( - common_data_ptr_, filtered_by_lanes_objects.target_lane_trailing); - const auto current_lane_extended_objects = utils::lane_change::transform_to_extended_objects( - common_data_ptr_, filtered_by_lanes_objects.current_lane); - const auto other_lane_extended_objects = utils::lane_change::transform_to_extended_objects( - common_data_ptr_, filtered_by_lanes_objects.other_lane); - - FilteredByLanesExtendedObjects lane_change_target_objects( - current_lane_extended_objects, target_lane_leading_extended_objects, - target_lane_trailing_extended_objects, other_lane_extended_objects); - lane_change_debug_.filtered_objects = lane_change_target_objects; - return lane_change_target_objects; + return filtered_objects; } void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const @@ -1038,7 +1072,8 @@ void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const const auto is_stopped_object = [](const auto & object) -> bool { constexpr double min_vel_th = -0.5; constexpr double max_vel_th = 0.5; - return utils::path_safety_checker::filter::velocity_filter(object, min_vel_th, max_vel_th); + return velocity_filter( + object.kinematics.initial_twist_with_covariance.twist, min_vel_th, max_vel_th); }; utils::path_safety_checker::filterObjects(objects, [&](const PredictedObject & object) { @@ -1051,122 +1086,6 @@ void NormalLaneChange::filterOncomingObjects(PredictedObjects & objects) const }); } -FilteredByLanesObjects NormalLaneChange::filterObjectsByLanelets( - const PredictedObjects & objects, const PathWithLaneId & current_lanes_ref_path) const -{ - std::vector target_lane_leading_objects; - std::vector target_lane_trailing_objects; - std::vector current_lane_objects; - std::vector other_lane_objects; - - const auto & current_pose = getEgoPose(); - const auto & current_lanes = common_data_ptr_->lanes_ptr->current; - const auto & target_lanes = common_data_ptr_->lanes_ptr->target; - const auto & route_handler = getRouteHandler(); - const auto & common_parameters = planner_data_->parameters; - const auto check_optional_polygon = [](const auto & object, const auto & polygon) { - return !polygon.empty() && isPolygonOverlapLanelet(object, polygon); - }; - - // get backward lanes - const auto & target_backward_lanes = common_data_ptr_->lanes_ptr->preceding_target; - - { - lane_change_debug_.current_lanes = current_lanes; - lane_change_debug_.target_lanes = target_lanes; - - // TODO(Azu) change the type to std::vector - lane_change_debug_.target_backward_lanes.clear(); - std::for_each( - target_backward_lanes.begin(), target_backward_lanes.end(), - [&](const lanelet::ConstLanelets & target_backward_lane) { - lane_change_debug_.target_backward_lanes.insert( - lane_change_debug_.target_backward_lanes.end(), target_backward_lane.begin(), - target_backward_lane.end()); - }); - } - - const auto & lanes_polygon = *common_data_ptr_->lanes_polygon_ptr; - const auto dist_ego_to_current_lanes_center = - lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, current_pose); - - const auto reserve_size = objects.objects.size(); - current_lane_objects.reserve(reserve_size); - target_lane_leading_objects.reserve(reserve_size); - target_lane_trailing_objects.reserve(reserve_size); - other_lane_objects.reserve(reserve_size); - - for (const auto & object : objects.objects) { - const auto is_lateral_far = std::invoke([&]() -> bool { - const auto dist_object_to_current_lanes_center = - lanelet::utils::getLateralDistanceToClosestLanelet( - current_lanes, object.kinematics.initial_pose_with_covariance.pose); - const auto lateral = dist_object_to_current_lanes_center - dist_ego_to_current_lanes_center; - return std::abs(lateral) > (common_parameters.vehicle_width / 2); - }); - - const auto is_before_terminal = [&]() { - return utils::lane_change::is_before_terminal( - common_data_ptr_, current_lanes_ref_path, object); - }; - - if ( - check_optional_polygon(object, lanes_polygon.target) && is_lateral_far && - is_before_terminal()) { - const auto ahead_of_ego = - utils::lane_change::is_ahead_of_ego(common_data_ptr_, current_lanes_ref_path, object); - if (ahead_of_ego) { - target_lane_leading_objects.push_back(object); - } else { - target_lane_trailing_objects.push_back(object); - } - continue; - } - - if ( - check_optional_polygon(object, lanes_polygon.expanded_target) && is_lateral_far && - is_before_terminal()) { - const auto ahead_of_ego = - utils::lane_change::is_ahead_of_ego(common_data_ptr_, current_lanes_ref_path, object); - const auto stopped_obj_vel_th = - common_data_ptr_->lc_param_ptr->stopped_object_velocity_threshold; - if (object.kinematics.initial_twist_with_covariance.twist.linear.x < stopped_obj_vel_th) { - if (ahead_of_ego) { - target_lane_leading_objects.push_back(object); - continue; - } - } - } - - const auto is_overlap_target_backward = std::invoke([&]() -> bool { - const auto check_backward_polygon = [&object](const auto & target_backward_polygon) { - return isPolygonOverlapLanelet(object, target_backward_polygon); - }; - return std::any_of( - lanes_polygon.preceding_target.begin(), lanes_polygon.preceding_target.end(), - check_backward_polygon); - }); - - // check if the object intersects with target backward lanes - if (is_overlap_target_backward) { - target_lane_trailing_objects.push_back(object); - continue; - } - - if (check_optional_polygon(object, lanes_polygon.current)) { - // check only the objects that are in front of the ego vehicle - current_lane_objects.push_back(object); - continue; - } - - other_lane_objects.push_back(object); - } - - return { - current_lane_objects, target_lane_leading_objects, target_lane_trailing_objects, - other_lane_objects}; -} - PathWithLaneId NormalLaneChange::getTargetSegment( const lanelet::ConstLanelets & target_lanes, const Pose & lane_changing_start_pose, const double target_lane_length, const double lane_changing_length, @@ -1420,7 +1339,7 @@ bool NormalLaneChange::check_candidate_path_safety( if ( !is_stuck && !utils::lane_change::passed_parked_objects( - common_data_ptr_, candidate_path, filtered_objects_.target_lane_leading, + common_data_ptr_, candidate_path, filtered_objects_.target_lane_leading.stopped, lane_change_debug_.collision_check_objects)) { throw std::logic_error( "Ego is not stuck and parked vehicle exists in the target lane. Skip lane change."); @@ -1601,7 +1520,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const } const auto has_passed_parked_objects = utils::lane_change::passed_parked_objects( - common_data_ptr_, path, filtered_objects_.target_lane_leading, debug_data); + common_data_ptr_, path, filtered_objects_.target_lane_leading.stopped, debug_data); if (!has_passed_parked_objects) { RCLCPP_DEBUG(logger_, "Lane change has been delayed."); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index 7aea478bd6794..5700842780395 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -101,36 +101,34 @@ MarkerArray createLaneChangingVirtualWallMarker( } MarkerArray showFilteredObjects( - const FilteredByLanesExtendedObjects & filtered_objects, const std::string & ns) + const FilteredLanesObjects & filtered_objects, const std::string & ns) { int32_t update_id = 0; - auto current_marker = marker_utils::showFilteredObjects( - filtered_objects.current_lane, ns, colors::yellow(), update_id); - update_id += static_cast(current_marker.markers.size()); - auto target_leading_marker = marker_utils::showFilteredObjects( - filtered_objects.target_lane_leading, ns, colors::aqua(), update_id); - update_id += static_cast(target_leading_marker.markers.size()); - auto target_trailing_marker = marker_utils::showFilteredObjects( - filtered_objects.target_lane_trailing, ns, colors::blue(), update_id); - update_id += static_cast(target_trailing_marker.markers.size()); - auto other_marker = marker_utils::showFilteredObjects( - filtered_objects.other_lane, ns, colors::medium_orchid(), update_id); - MarkerArray marker_array; - std::move( - current_marker.markers.begin(), current_marker.markers.end(), - std::back_inserter(marker_array.markers)); - std::move( - target_leading_marker.markers.begin(), target_leading_marker.markers.end(), - std::back_inserter(marker_array.markers)); - - std::move( - target_trailing_marker.markers.begin(), target_trailing_marker.markers.end(), - std::back_inserter(marker_array.markers)); - - std::move( - other_marker.markers.begin(), other_marker.markers.end(), - std::back_inserter(marker_array.markers)); + auto reserve_size = filtered_objects.current_lane.size() + filtered_objects.others.size() + + filtered_objects.target_lane_leading.size() + + filtered_objects.target_lane_trailing.size(); + marker_array.markers.reserve(2 * reserve_size); + auto add_objects_to_marker = + [&](const ExtendedPredictedObjects & objects, const ColorRGBA & color) { + if (objects.empty()) { + return; + } + + auto marker = marker_utils::showFilteredObjects(objects, ns, color, update_id); + update_id += static_cast(marker.markers.size()); + std::move( + marker.markers.begin(), marker.markers.end(), std::back_inserter(marker_array.markers)); + }; + + add_objects_to_marker(filtered_objects.current_lane, colors::yellow()); + add_objects_to_marker(filtered_objects.target_lane_leading.moving, colors::aqua()); + add_objects_to_marker(filtered_objects.target_lane_leading.stopped, colors::light_steel_blue()); + add_objects_to_marker(filtered_objects.target_lane_trailing, colors::blue()); + add_objects_to_marker( + filtered_objects.target_lane_leading.stopped_at_bound, colors::light_pink()); + add_objects_to_marker(filtered_objects.others, colors::medium_orchid()); + return marker_array; } 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 69cf6441ef766..49551aa73f635 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 @@ -25,6 +25,7 @@ #include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" +#include #include #include #include @@ -33,6 +34,7 @@ #include #include #include +#include #include #include @@ -912,9 +914,7 @@ lanelet::BasicPolygon2d create_polygon( } ExtendedPredictedObject transform( - const PredictedObject & object, - [[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters) + const PredictedObject & object, const LaneChangeParameters & lane_change_parameters) { ExtendedPredictedObject extended_object(object); @@ -1078,21 +1078,15 @@ bool is_same_lane_with_prev_iteration( bool is_ahead_of_ego( const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, - const PredictedObject & object) + const ExtendedPredictedObject & object) { - const auto & current_ego_pose = common_data_ptr->get_ego_pose(); - - const auto & obj_position = object.kinematics.initial_pose_with_covariance.pose.position; - - const auto dist_to_base_link = autoware::motion_utils::calcSignedArcLength( - path.points, current_ego_pose.position, obj_position); const auto & ego_info = common_data_ptr->bpp_param_ptr->vehicle_info; const auto lon_dev = std::max( ego_info.max_longitudinal_offset_m + ego_info.rear_overhang_m, object.shape.dimensions.x); // we don't always have to check the distance accurately. - if (std::abs(dist_to_base_link) > lon_dev) { - return dist_to_base_link >= 0.0; + if (std::abs(object.dist_from_ego) > lon_dev) { + return object.dist_from_ego >= 0.0; } const auto & current_footprint = common_data_ptr->transient_data.current_footprint.outer(); @@ -1105,9 +1099,8 @@ bool is_ahead_of_ego( ego_min_dist_to_end = std::min(dist_to_end, ego_min_dist_to_end); } - const auto obj_polygon = autoware::universe_utils::toPolygon2d(object).outer(); auto current_min_dist_to_end = std::numeric_limits::max(); - for (const auto & polygon_p : obj_polygon) { + for (const auto & polygon_p : object.initial_polygon.outer()) { const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); const auto dist_ego_to_obj = autoware::motion_utils::calcSignedArcLength( path.points, obj_p, path.points.back().point.pose.position); @@ -1118,7 +1111,7 @@ bool is_ahead_of_ego( bool is_before_terminal( const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, - const PredictedObject & object) + const ExtendedPredictedObject & object) { const auto & route_handler_ptr = common_data_ptr->route_handler_ptr; const auto & lanes_ptr = common_data_ptr->lanes_ptr; @@ -1127,7 +1120,7 @@ bool is_before_terminal( : path.points.back().point.pose.position; double current_max_dist = std::numeric_limits::lowest(); - const auto & obj_position = object.kinematics.initial_pose_with_covariance.pose.position; + const auto & obj_position = object.initial_pose.position; const auto dist_to_base_link = autoware::motion_utils::calcSignedArcLength(path.points, obj_position, terminal_position); // we don't always have to check the distance accurately. @@ -1135,8 +1128,7 @@ bool is_before_terminal( return dist_to_base_link >= 0.0; } - const auto obj_polygon = autoware::universe_utils::toPolygon2d(object).outer(); - for (const auto & polygon_p : obj_polygon) { + for (const auto & polygon_p : object.initial_polygon.outer()) { const auto obj_p = autoware::universe_utils::createPoint(polygon_p.x(), polygon_p.y(), 0.0); const auto dist_obj_to_terminal = autoware::motion_utils::calcSignedArcLength(path.points, obj_p, terminal_position); @@ -1156,22 +1148,6 @@ double calc_angle_to_lanelet_segment(const lanelet::ConstLanelets & lanelets, co return std::abs(autoware::universe_utils::calcYawDeviation(closest_pose, pose)); } -ExtendedPredictedObjects transform_to_extended_objects( - const CommonDataPtr & common_data_ptr, const std::vector & objects) -{ - ExtendedPredictedObjects extended_objects; - extended_objects.reserve(objects.size()); - - const auto & bpp_param = *common_data_ptr->bpp_param_ptr; - const auto & lc_param = *common_data_ptr->lc_param_ptr; - std::transform( - objects.begin(), objects.end(), std::back_inserter(extended_objects), [&](const auto & object) { - return utils::lane_change::transform(object, bpp_param, lc_param); - }); - - return extended_objects; -} - double get_distance_to_next_regulatory_element( const CommonDataPtr & common_data_ptr, const bool ignore_crosswalk, const bool ignore_intersection) @@ -1200,7 +1176,7 @@ double get_distance_to_next_regulatory_element( } double get_min_dist_to_current_lanes_obj( - const CommonDataPtr & common_data_ptr, const FilteredByLanesExtendedObjects & filtered_objects, + const CommonDataPtr & common_data_ptr, const FilteredLanesObjects & filtered_objects, const double dist_to_target_lane_start, const PathWithLaneId & path) { const auto & path_points = path.points; @@ -1240,28 +1216,15 @@ double get_min_dist_to_current_lanes_obj( } bool has_blocking_target_object( - const CommonDataPtr & common_data_ptr, const FilteredByLanesExtendedObjects & filtered_objects, - const double stop_arc_length, const PathWithLaneId & path) + const TargetLaneLeadingObjects & target_leading_objects, const double stop_arc_length, + const PathWithLaneId & path) { - return std::any_of( - filtered_objects.target_lane_leading.begin(), filtered_objects.target_lane_leading.end(), - [&](const auto & object) { - const auto v = std::abs(object.initial_twist.linear.x); - if (v > common_data_ptr->lc_param_ptr->stop_velocity_threshold) { - return false; - } - - // filtered_objects includes objects out of target lanes, so filter them out - if (boost::geometry::disjoint( - object.initial_polygon, common_data_ptr->lanes_polygon_ptr->target)) { - return false; - } - - const auto arc_length_to_target_lane_obj = motion_utils::calcSignedArcLength( - path.points, path.points.front().point.pose.position, object.initial_pose.position); - const auto width_margin = object.shape.dimensions.x / 2; - return (arc_length_to_target_lane_obj - width_margin) >= stop_arc_length; - }); + return ranges::any_of(target_leading_objects.stopped, [&](const auto & object) { + const auto arc_length_to_target_lane_obj = motion_utils::calcSignedArcLength( + path.points, path.points.front().point.pose.position, object.initial_pose.position); + const auto width_margin = object.shape.dimensions.x / 2; + return (arc_length_to_target_lane_obj - width_margin) >= stop_arc_length; + }); } bool has_passed_intersection_turn_direction(const CommonDataPtr & common_data_ptr) @@ -1323,4 +1286,68 @@ bool has_overtaking_turn_lane_object( return std::any_of( trailing_objects.begin(), trailing_objects.end(), is_object_overlap_with_target); } + +bool filter_target_lane_objects( + const CommonDataPtr & common_data_ptr, const ExtendedPredictedObject & object, + const double dist_ego_to_current_lanes_center, const bool ahead_of_ego, + const bool before_terminal, TargetLaneLeadingObjects & leading_objects, + ExtendedPredictedObjects & trailing_objects) +{ + using behavior_path_planner::utils::path_safety_checker::filter::velocity_filter; + const auto & current_lanes = common_data_ptr->lanes_ptr->current; + const auto & vehicle_width = common_data_ptr->bpp_param_ptr->vehicle_info.vehicle_width_m; + const auto & lanes_polygon = *common_data_ptr->lanes_polygon_ptr; + const auto stopped_obj_vel_th = common_data_ptr->lc_param_ptr->stopped_object_velocity_threshold; + + const auto is_lateral_far = std::invoke([&]() -> bool { + const auto dist_object_to_current_lanes_center = + lanelet::utils::getLateralDistanceToClosestLanelet(current_lanes, object.initial_pose); + const auto lateral = dist_object_to_current_lanes_center - dist_ego_to_current_lanes_center; + return std::abs(lateral) > (vehicle_width / 2); + }); + + const auto is_stopped = velocity_filter( + object.initial_twist, -std::numeric_limits::epsilon(), stopped_obj_vel_th); + if (is_lateral_far && before_terminal) { + const auto in_target_lanes = + !boost::geometry::disjoint(object.initial_polygon, lanes_polygon.target); + if (in_target_lanes) { + if (!ahead_of_ego && !is_stopped) { + trailing_objects.push_back(object); + return true; + } + + if (ahead_of_ego) { + if (is_stopped) { + leading_objects.stopped.push_back(object); + } else { + leading_objects.moving.push_back(object); + } + return true; + } + } + + // Check if the object is positioned outside the lane boundary but still close to its edge. + const auto in_expanded_target_lanes = + !boost::geometry::disjoint(object.initial_polygon, lanes_polygon.expanded_target); + + if (in_expanded_target_lanes && is_stopped && ahead_of_ego) { + leading_objects.stopped_at_bound.push_back(object); + return true; + } + } + + const auto is_overlap_target_backward = + ranges::any_of(lanes_polygon.preceding_target, [&](const auto & target_backward_polygon) { + return !boost::geometry::disjoint(object.initial_polygon, target_backward_polygon); + }); + + // check if the object intersects with target backward lanes + if (is_overlap_target_backward && !is_stopped) { + trailing_objects.push_back(object); + return true; + } + + return false; +} } // namespace autoware::behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index d9873975dabe1..5c29f347ad9ef 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -37,13 +37,12 @@ using tier4_planning_msgs::msg::PathPointWithLaneId; /** * @brief Filters object based on velocity. * - * @param object The predicted object to filter. + * @param twist The twist of predicted object to filter. * @param velocity_threshold Lower bound * @param max_velocity Upper bound * @return Returns true when the object is within a certain velocity range. */ -bool velocity_filter( - const PredictedObject & object, double velocity_threshold, double max_velocity); +bool velocity_filter(const Twist & object_twist, double velocity_threshold, double max_velocity); /** * @brief Filters object based on position. diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 80936b655cc48..3c1d9f194aeec 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -26,11 +26,9 @@ namespace autoware::behavior_path_planner::utils::path_safety_checker::filter { -bool velocity_filter(const PredictedObject & object, double velocity_threshold, double max_velocity) +bool velocity_filter(const Twist & object_twist, double velocity_threshold, double max_velocity) { - const auto v_norm = std::hypot( - object.kinematics.initial_twist_with_covariance.twist.linear.x, - object.kinematics.initial_twist_with_covariance.twist.linear.y); + const auto v_norm = std::hypot(object_twist.linear.x, object_twist.linear.y); return (velocity_threshold < v_norm && v_norm < max_velocity); } @@ -148,7 +146,8 @@ PredictedObjects filterObjectsByVelocity( const PredictedObjects & objects, double velocity_threshold, double max_velocity) { const auto filter = [&](const auto & object) { - return filter::velocity_filter(object, velocity_threshold, max_velocity); + return filter::velocity_filter( + object.kinematics.initial_twist_with_covariance.twist, velocity_threshold, max_velocity); }; auto filtered = objects; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp index a2058db51c9ea..88ed968d27b64 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp @@ -66,13 +66,14 @@ TEST(BehaviorPathPlanningObjectsFiltering, velocity_filter) using autoware::behavior_path_planner::utils::path_safety_checker::filter::velocity_filter; PredictedObject predicted_obj; - predicted_obj.kinematics.initial_twist_with_covariance.twist.linear.x = 4.0; - predicted_obj.kinematics.initial_twist_with_covariance.twist.linear.y = 3.0; - - EXPECT_TRUE(velocity_filter(predicted_obj, 4.0, 10.0)); - EXPECT_FALSE(velocity_filter(predicted_obj, 6.0, 10.0)); - EXPECT_FALSE(velocity_filter(predicted_obj, 2.0, 4.9)); - EXPECT_FALSE(velocity_filter(predicted_obj, 6.0, 2.0)); + auto & twist = predicted_obj.kinematics.initial_twist_with_covariance.twist; + twist.linear.x = 4.0; + twist.linear.y = 3.0; + + EXPECT_TRUE(velocity_filter(twist, 4.0, 10.0)); + EXPECT_FALSE(velocity_filter(twist, 6.0, 10.0)); + EXPECT_FALSE(velocity_filter(twist, 2.0, 4.9)); + EXPECT_FALSE(velocity_filter(twist, 6.0, 2.0)); } TEST(BehaviorPathPlanningObjectsFiltering, position_filter) From 740d42a80cd420a1221e9a1b38e94c767c8527f8 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Fri, 22 Nov 2024 17:21:25 +0900 Subject: [PATCH 096/273] chore(behavior_path_planner_common): add package maintainer (#9429) add package maintainer Signed-off-by: mohammad alqudah --- .../autoware_behavior_path_planner_common/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml index 5b925bd5ffd8e..bd32cf42293a7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml @@ -26,6 +26,7 @@ Takamasa Horibe Zulfaqar Azmi Go Sakayori + Alqudah Mohammad Apache License 2.0 From 83f6391c4bf1a53075a6a5c392a592563ba0cb3f Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 25 Nov 2024 12:54:04 +0900 Subject: [PATCH 097/273] feat(pyplot): add C++ pyplot (#9430) Signed-off-by: Mamoru Sobue --- common/autoware_pyplot/CMakeLists.txt | 32 +++ .../include/autoware/pyplot/axes.hpp | 141 ++++++++++++ .../include/autoware/pyplot/common.hpp | 44 ++++ .../include/autoware/pyplot/figure.hpp | 62 ++++++ .../include/autoware/pyplot/legend.hpp | 32 +++ .../include/autoware/pyplot/loader.hpp | 28 +++ .../include/autoware/pyplot/patches.hpp | 57 +++++ .../include/autoware/pyplot/pyplot.hpp | 164 ++++++++++++++ .../include/autoware/pyplot/quiver.hpp | 32 +++ .../include/autoware/pyplot/text.hpp | 40 ++++ common/autoware_pyplot/package.xml | 25 +++ common/autoware_pyplot/src/axes.cpp | 154 +++++++++++++ common/autoware_pyplot/src/common.cpp | 30 +++ common/autoware_pyplot/src/figure.cpp | 66 ++++++ common/autoware_pyplot/src/legend.cpp | 28 +++ common/autoware_pyplot/src/patches.cpp | 45 ++++ common/autoware_pyplot/src/pyplot.cpp | 205 ++++++++++++++++++ common/autoware_pyplot/src/quiver.cpp | 28 +++ common/autoware_pyplot/src/text.cpp | 35 +++ common/autoware_pyplot/test/test_pyplot.cpp | 64 ++++++ 20 files changed, 1312 insertions(+) create mode 100644 common/autoware_pyplot/CMakeLists.txt create mode 100644 common/autoware_pyplot/include/autoware/pyplot/axes.hpp create mode 100644 common/autoware_pyplot/include/autoware/pyplot/common.hpp create mode 100644 common/autoware_pyplot/include/autoware/pyplot/figure.hpp create mode 100644 common/autoware_pyplot/include/autoware/pyplot/legend.hpp create mode 100644 common/autoware_pyplot/include/autoware/pyplot/loader.hpp create mode 100644 common/autoware_pyplot/include/autoware/pyplot/patches.hpp create mode 100644 common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp create mode 100644 common/autoware_pyplot/include/autoware/pyplot/quiver.hpp create mode 100644 common/autoware_pyplot/include/autoware/pyplot/text.hpp create mode 100644 common/autoware_pyplot/package.xml create mode 100644 common/autoware_pyplot/src/axes.cpp create mode 100644 common/autoware_pyplot/src/common.cpp create mode 100644 common/autoware_pyplot/src/figure.cpp create mode 100644 common/autoware_pyplot/src/legend.cpp create mode 100644 common/autoware_pyplot/src/patches.cpp create mode 100644 common/autoware_pyplot/src/pyplot.cpp create mode 100644 common/autoware_pyplot/src/quiver.cpp create mode 100644 common/autoware_pyplot/src/text.cpp create mode 100644 common/autoware_pyplot/test/test_pyplot.cpp diff --git a/common/autoware_pyplot/CMakeLists.txt b/common/autoware_pyplot/CMakeLists.txt new file mode 100644 index 0000000000000..6922d5d9306f7 --- /dev/null +++ b/common/autoware_pyplot/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 3.14) + +project(autoware_pyplot) + +find_package(autoware_cmake REQUIRED) + +find_package( + Python3 + COMPONENTS Interpreter Development + REQUIRED) +find_package(pybind11 REQUIRED) + +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} STATIC + DIRECTORY src +) +target_link_libraries(${PROJECT_NAME} ${Python3_LIBRARIES} pybind11::embed) + +if(BUILD_TESTING) + find_package(ament_cmake_ros REQUIRED) + + file(GLOB_RECURSE test_files test/*.cpp) + + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} ${test_files}) + + target_link_libraries(test_${PROJECT_NAME} + ${PROJECT_NAME} + ) +endif() + +ament_auto_package() diff --git a/common/autoware_pyplot/include/autoware/pyplot/axes.hpp b/common/autoware_pyplot/include/autoware/pyplot/axes.hpp new file mode 100644 index 0000000000000..53eb2daf21b8f --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/axes.hpp @@ -0,0 +1,141 @@ +// 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__PYPLOT__AXES_HPP_ +#define AUTOWARE__PYPLOT__AXES_HPP_ + +#include +#include +#include + +#include + +namespace autoware::pyplot +{ +inline namespace axes +{ +class DECL_VISIBILITY Axes : public PyObjectWrapper +{ +public: + explicit Axes(const pybind11::object & object); + explicit Axes(pybind11::object && object); + + PyObjectWrapper add_patch( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper bar_label( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper cla( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper contour( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper errorbar( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper fill( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper fill_between( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + std::tuple get_xlim() const; + + std::tuple get_ylim() const; + + PyObjectWrapper grid( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper imshow( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + legend::Legend legend( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper plot( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + quiver::Quiver quiver( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_aspect( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_title( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_xlabel( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_xlim( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_ylabel( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper set_ylim( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper text( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + +private: + void load_attrs(); + + pybind11::object add_patch_attr; + pybind11::object cla_attr; + pybind11::object contour_attr; + pybind11::object contourf_attr; + pybind11::object fill_attr; + pybind11::object fill_between_attr; + pybind11::object get_xlim_attr; + pybind11::object get_ylim_attr; + pybind11::object grid_attr; + pybind11::object imshow_attr; + pybind11::object legend_attr; + pybind11::object quiver_attr; + pybind11::object plot_attr; + pybind11::object scatter_attr; + pybind11::object set_aspect_attr; + pybind11::object set_title_attr; + pybind11::object set_xlabel_attr; + pybind11::object set_xlim_attr; + pybind11::object set_ylabel_attr; + pybind11::object set_ylim_attr; + pybind11::object text_attr; +}; +} // namespace axes +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__AXES_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/common.hpp b/common/autoware_pyplot/include/autoware/pyplot/common.hpp new file mode 100644 index 0000000000000..123bd82029e08 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/common.hpp @@ -0,0 +1,44 @@ +// 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__PYPLOT__COMMON_HPP_ +#define AUTOWARE__PYPLOT__COMMON_HPP_ + +#include + +namespace autoware::pyplot +{ + +#ifdef _WIN32 +#define DECL_VISIBILITY __declspec(dllexport) +#else +#define DECL_VISIBILITY __attribute__((visibility("hidden"))) +#endif + +inline namespace common +{ +class DECL_VISIBILITY PyObjectWrapper +{ +public: + explicit PyObjectWrapper(const pybind11::object & object); + explicit PyObjectWrapper(pybind11::object && object); + pybind11::object unwrap() const { return self_; } + +protected: + pybind11::object self_; +}; +} // namespace common +} // namespace autoware::pyplot + +#endif // AUTOWARE__PYPLOT__COMMON_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/figure.hpp b/common/autoware_pyplot/include/autoware/pyplot/figure.hpp new file mode 100644 index 0000000000000..d438682d5b368 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/figure.hpp @@ -0,0 +1,62 @@ +// 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__PYPLOT__FIGURE_HPP_ +#define AUTOWARE__PYPLOT__FIGURE_HPP_ + +#include +#include + +namespace autoware::pyplot +{ +inline namespace figure +{ +class DECL_VISIBILITY Figure : public PyObjectWrapper +{ +public: + explicit Figure(const pybind11::object & object); + explicit Figure(pybind11::object && object); + + axes::Axes add_axes( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + axes::Axes add_subplot( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper colorbar( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper savefig( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + + PyObjectWrapper tight_layout( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + +private: + void load_attrs(); + + pybind11::object add_axes_attr; + pybind11::object add_subplot_attr; + pybind11::object colorbar_attr; + pybind11::object savefig_attr; + pybind11::object tight_layout_attr; +}; +} // namespace figure +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__FIGURE_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/legend.hpp b/common/autoware_pyplot/include/autoware/pyplot/legend.hpp new file mode 100644 index 0000000000000..853f1e288407c --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/legend.hpp @@ -0,0 +1,32 @@ +// 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__PYPLOT__LEGEND_HPP_ +#define AUTOWARE__PYPLOT__LEGEND_HPP_ + +#include + +namespace autoware::pyplot +{ +inline namespace legend +{ +class DECL_VISIBILITY Legend : public PyObjectWrapper +{ +public: + explicit Legend(const pybind11::object & object); + explicit Legend(pybind11::object && object); +}; +} // namespace legend +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__LEGEND_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/loader.hpp b/common/autoware_pyplot/include/autoware/pyplot/loader.hpp new file mode 100644 index 0000000000000..df44c257d5925 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/loader.hpp @@ -0,0 +1,28 @@ +// 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__PYPLOT__LOADER_HPP_ +#define AUTOWARE__PYPLOT__LOADER_HPP_ + +namespace autoware::pyplot +{ + +#define LOAD_FUNC_ATTR(obj, mod) \ + do { \ + obj##_attr = mod.attr(#obj); \ + } while (0) + +} // namespace autoware::pyplot + +#endif // AUTOWARE__PYPLOT__LOADER_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/patches.hpp b/common/autoware_pyplot/include/autoware/pyplot/patches.hpp new file mode 100644 index 0000000000000..0c6c545942c74 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/patches.hpp @@ -0,0 +1,57 @@ +// 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__PYPLOT__PATCHES_HPP_ +#define AUTOWARE__PYPLOT__PATCHES_HPP_ + +#include + +namespace autoware::pyplot +{ +inline namespace patches +{ +class DECL_VISIBILITY Circle : public PyObjectWrapper +{ +public: + explicit Circle( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); +}; + +class DECL_VISIBILITY Ellipse : public PyObjectWrapper +{ +public: + explicit Ellipse( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); +}; + +class DECL_VISIBILITY Rectangle : public PyObjectWrapper +{ +public: + explicit Rectangle( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); +}; + +class DECL_VISIBILITY Polygon : public PyObjectWrapper +{ +public: + explicit Polygon( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); +}; +} // namespace patches +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__PATCHES_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp b/common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp new file mode 100644 index 0000000000000..83e0febeb237f --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp @@ -0,0 +1,164 @@ +// 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__PYPLOT__PYPLOT_HPP_ +#define AUTOWARE__PYPLOT__PYPLOT_HPP_ + +#include +#include +#include + +#include +#include +#include + +namespace autoware::pyplot +{ +struct DECL_VISIBILITY PyPlot +{ +public: + explicit PyPlot(const pybind11::module & mod_); + + axes::Axes axes(const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper axis( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper cla( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper clf( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + figure::Figure figure( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + axes::Axes gca( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + figure::Figure gcf( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper gci( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper grid( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper imshow( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper legend( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper plot( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper quiver( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper savefig( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper scatter( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper show( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + axes::Axes subplot(const pybind11::dict & kwargs = pybind11::dict()); + axes::Axes subplot(int cri); + + std::tuple subplots(const pybind11::dict & kwargs = pybind11::dict()); + std::tuple> subplots( + int r, int c, const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper title( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper xlabel( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper xlim( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper ylabel( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + + PyObjectWrapper ylim( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()); + +private: + void load_attrs(); + pybind11::module mod; + pybind11::object axes_attr; + pybind11::object cla_attr; + pybind11::object clf_attr; + pybind11::object figure_attr; + pybind11::object gca_attr; + pybind11::object gcf_attr; + pybind11::object gci_attr; + pybind11::object grid_attr; + pybind11::object imshow_attr; + pybind11::object legend_attr; + pybind11::object plot_attr; + pybind11::object quiver_attr; + pybind11::object savefig_attr; + pybind11::object scatter_attr; + pybind11::object show_attr; + pybind11::object subplot_attr; + pybind11::object subplots_attr; + pybind11::object title_attr; + pybind11::object xlabel_attr; + pybind11::object xlim_attr; + pybind11::object ylabel_attr; + pybind11::object ylim_attr; +}; + +PyPlot import(); + +} // namespace autoware::pyplot + +template +pybind11::tuple Args(ArgsT &&... args) +{ + return pybind11::make_tuple(std::forward(args)...); +} + +using Kwargs = pybind11::dict; + +namespace py = pybind11; +using namespace py::literals; + +#endif // AUTOWARE__PYPLOT__PYPLOT_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/quiver.hpp b/common/autoware_pyplot/include/autoware/pyplot/quiver.hpp new file mode 100644 index 0000000000000..443c0540d9308 --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/quiver.hpp @@ -0,0 +1,32 @@ +// 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__PYPLOT__QUIVER_HPP_ +#define AUTOWARE__PYPLOT__QUIVER_HPP_ + +#include + +namespace autoware::pyplot +{ +inline namespace quiver +{ +class DECL_VISIBILITY Quiver : public PyObjectWrapper +{ +public: + explicit Quiver(const pybind11::object & object); + explicit Quiver(pybind11::object && object); +}; +} // namespace quiver +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__QUIVER_HPP_ diff --git a/common/autoware_pyplot/include/autoware/pyplot/text.hpp b/common/autoware_pyplot/include/autoware/pyplot/text.hpp new file mode 100644 index 0000000000000..27f892e90488f --- /dev/null +++ b/common/autoware_pyplot/include/autoware/pyplot/text.hpp @@ -0,0 +1,40 @@ +// 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__PYPLOT__TEXT_HPP_ +#define AUTOWARE__PYPLOT__TEXT_HPP_ + +#include + +namespace autoware::pyplot +{ +inline namespace text +{ +class DECL_VISIBILITY Text : public PyObjectWrapper +{ +public: + explicit Text(const pybind11::object & object); + explicit Text(pybind11::object && object); + + PyObjectWrapper set_rotation( + const pybind11::tuple & args = pybind11::tuple(), + const pybind11::dict & kwargs = pybind11::dict()) const; + +private: + void load_attrs(); + pybind11::object set_rotation_attr; +}; +} // namespace text +} // namespace autoware::pyplot +#endif // AUTOWARE__PYPLOT__TEXT_HPP_ diff --git a/common/autoware_pyplot/package.xml b/common/autoware_pyplot/package.xml new file mode 100644 index 0000000000000..1391db88cddff --- /dev/null +++ b/common/autoware_pyplot/package.xml @@ -0,0 +1,25 @@ + + + + autoware_pyplot + 0.1.0 + C++ interface for matplotlib based on pybind11 + Mamoru Sobue + Yukinari Hisaki + Apache License 2.0 + + Mamoru Sobue + + ament_cmake_auto + autoware_cmake + + pybind11-dev + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/common/autoware_pyplot/src/axes.cpp b/common/autoware_pyplot/src/axes.cpp new file mode 100644 index 0000000000000..0f08ffe5773f6 --- /dev/null +++ b/common/autoware_pyplot/src/axes.cpp @@ -0,0 +1,154 @@ +// 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::pyplot +{ +inline namespace axes +{ +Axes::Axes(const pybind11::object & object) : PyObjectWrapper(object) +{ + load_attrs(); +} +Axes::Axes(pybind11::object && object) : PyObjectWrapper(object) +{ + load_attrs(); +} + +PyObjectWrapper Axes::add_patch(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{add_patch_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::cla(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{cla_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::contour(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{contour_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::fill(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{fill_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::fill_between( + const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{fill_between_attr(*args, **kwargs)}; +} + +std::tuple Axes::get_xlim() const +{ + const pybind11::list ret = get_xlim_attr(); + return {ret[0].cast(), ret[1].cast()}; +} + +std::tuple Axes::get_ylim() const +{ + const pybind11::list ret = get_ylim_attr(); + return {ret[0].cast(), ret[1].cast()}; +} + +PyObjectWrapper Axes::grid(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{grid_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::imshow(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{imshow_attr(*args, **kwargs)}; +} + +legend::Legend Axes::legend(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return legend::Legend{legend_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::plot(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{plot_attr(*args, **kwargs)}; +} + +quiver::Quiver Axes::quiver(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return Quiver{quiver_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_aspect(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_aspect_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_title(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_title_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_xlabel(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_xlabel_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_xlim(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_xlim_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_ylabel(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_ylabel_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::set_ylim(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{set_ylim_attr(*args, **kwargs)}; +} + +PyObjectWrapper Axes::text(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{text_attr(*args, **kwargs)}; +} + +void Axes::load_attrs() +{ + LOAD_FUNC_ATTR(add_patch, self_); + LOAD_FUNC_ATTR(cla, self_); + LOAD_FUNC_ATTR(contour, self_); + LOAD_FUNC_ATTR(contourf, self_); + LOAD_FUNC_ATTR(fill, self_); + LOAD_FUNC_ATTR(fill_between, self_); + LOAD_FUNC_ATTR(get_xlim, self_); + LOAD_FUNC_ATTR(get_ylim, self_); + LOAD_FUNC_ATTR(grid, self_); + LOAD_FUNC_ATTR(imshow, self_); + LOAD_FUNC_ATTR(legend, self_); + LOAD_FUNC_ATTR(quiver, self_); + LOAD_FUNC_ATTR(plot, self_); + LOAD_FUNC_ATTR(scatter, self_); + LOAD_FUNC_ATTR(set_aspect, self_); + LOAD_FUNC_ATTR(set_title, self_); + LOAD_FUNC_ATTR(set_xlabel, self_); + LOAD_FUNC_ATTR(set_xlim, self_); + LOAD_FUNC_ATTR(set_ylabel, self_); + LOAD_FUNC_ATTR(set_ylim, self_); + LOAD_FUNC_ATTR(text, self_); +} +} // namespace axes +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/common.cpp b/common/autoware_pyplot/src/common.cpp new file mode 100644 index 0000000000000..5b3fffa37f30e --- /dev/null +++ b/common/autoware_pyplot/src/common.cpp @@ -0,0 +1,30 @@ +// 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 + +namespace autoware::pyplot +{ +inline namespace common +{ +PyObjectWrapper::PyObjectWrapper(const pybind11::object & object) +{ + self_ = object; +} +PyObjectWrapper::PyObjectWrapper(pybind11::object && object) +{ + self_ = std::move(object); +} +} // namespace common +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/figure.cpp b/common/autoware_pyplot/src/figure.cpp new file mode 100644 index 0000000000000..07aacf8dd516a --- /dev/null +++ b/common/autoware_pyplot/src/figure.cpp @@ -0,0 +1,66 @@ +// 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::pyplot +{ +inline namespace figure +{ +Figure::Figure(const pybind11::object & object) : PyObjectWrapper(object) +{ + load_attrs(); +} +Figure::Figure(pybind11::object && object) : PyObjectWrapper(object) +{ + load_attrs(); +} + +void Figure::load_attrs() +{ + LOAD_FUNC_ATTR(add_axes, self_); + LOAD_FUNC_ATTR(add_subplot, self_); + LOAD_FUNC_ATTR(colorbar, self_); + LOAD_FUNC_ATTR(savefig, self_); + LOAD_FUNC_ATTR(tight_layout, self_); +} + +axes::Axes Figure::add_axes(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return axes::Axes{add_axes_attr(*args, **kwargs)}; +} + +axes::Axes Figure::add_subplot(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return axes::Axes{add_subplot_attr(*args, **kwargs)}; +} + +PyObjectWrapper Figure::colorbar(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{colorbar_attr(*args, **kwargs)}; +} + +PyObjectWrapper Figure::savefig(const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{savefig_attr(*args, **kwargs)}; +} + +PyObjectWrapper Figure::tight_layout( + const pybind11::tuple & args, const pybind11::dict & kwargs) const +{ + return PyObjectWrapper{tight_layout_attr(*args, **kwargs)}; +} +} // namespace figure +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/legend.cpp b/common/autoware_pyplot/src/legend.cpp new file mode 100644 index 0000000000000..e5a128725fec7 --- /dev/null +++ b/common/autoware_pyplot/src/legend.cpp @@ -0,0 +1,28 @@ +// 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 + +namespace autoware::pyplot +{ +inline namespace legend +{ +Legend::Legend(const pybind11::object & object) : PyObjectWrapper(object) +{ +} +Legend::Legend(pybind11::object && object) : PyObjectWrapper(object) +{ +} +} // namespace legend +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/patches.cpp b/common/autoware_pyplot/src/patches.cpp new file mode 100644 index 0000000000000..4df4de27e81e3 --- /dev/null +++ b/common/autoware_pyplot/src/patches.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 + +namespace autoware::pyplot +{ +inline namespace patches +{ +Circle::Circle(const pybind11::tuple & args, const pybind11::dict & kwargs) +: PyObjectWrapper(pybind11::module::import("matplotlib.patches").attr("Circle")) +{ + self_ = self_(*args, **kwargs); +} + +Ellipse::Ellipse(const pybind11::tuple & args, const pybind11::dict & kwargs) +: PyObjectWrapper(pybind11::module::import("matplotlib.patches").attr("Ellipse")) +{ + self_ = self_(*args, **kwargs); +} + +Rectangle::Rectangle(const pybind11::tuple & args, const pybind11::dict & kwargs) +: PyObjectWrapper(pybind11::module::import("matplotlib.patches").attr("Rectangle")) +{ + self_ = self_(*args, **kwargs); +} + +Polygon::Polygon(const pybind11::tuple & args, const pybind11::dict & kwargs) +: PyObjectWrapper(pybind11::module::import("matplotlib.patches").attr("Polygon")) +{ + self_ = self_(*args, **kwargs); +} +} // namespace patches +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/pyplot.cpp b/common/autoware_pyplot/src/pyplot.cpp new file mode 100644 index 0000000000000..d45d34a35d767 --- /dev/null +++ b/common/autoware_pyplot/src/pyplot.cpp @@ -0,0 +1,205 @@ +// 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::pyplot +{ +PyPlot::PyPlot(const pybind11::module & mod_) : mod(mod_) +{ + load_attrs(); +} + +void PyPlot::load_attrs() +{ + LOAD_FUNC_ATTR(axes, mod); + LOAD_FUNC_ATTR(cla, mod); + LOAD_FUNC_ATTR(clf, mod); + LOAD_FUNC_ATTR(figure, mod); + LOAD_FUNC_ATTR(gca, mod); + LOAD_FUNC_ATTR(gcf, mod); + LOAD_FUNC_ATTR(gci, mod); + LOAD_FUNC_ATTR(grid, mod); + LOAD_FUNC_ATTR(imshow, mod); + LOAD_FUNC_ATTR(legend, mod); + LOAD_FUNC_ATTR(plot, mod); + LOAD_FUNC_ATTR(quiver, mod); + LOAD_FUNC_ATTR(savefig, mod); + LOAD_FUNC_ATTR(scatter, mod); + LOAD_FUNC_ATTR(show, mod); + LOAD_FUNC_ATTR(subplot, mod); + LOAD_FUNC_ATTR(subplots, mod); + LOAD_FUNC_ATTR(title, mod); + LOAD_FUNC_ATTR(xlabel, mod); + LOAD_FUNC_ATTR(xlim, mod); + LOAD_FUNC_ATTR(ylabel, mod); + LOAD_FUNC_ATTR(ylim, mod); +} + +axes::Axes PyPlot::axes(const pybind11::dict & kwargs) +{ + return axes::Axes{axes_attr(**kwargs)}; +} + +PyObjectWrapper PyPlot::cla(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{cla_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::clf(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{clf_attr(*args, **kwargs)}; +} + +figure::Figure PyPlot::figure(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return figure::Figure{figure_attr(*args, **kwargs)}; +} + +axes::Axes PyPlot::gca(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return axes::Axes{gca_attr(*args, **kwargs)}; +} + +figure::Figure PyPlot::gcf(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return figure::Figure{gcf_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::gci(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{gci_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::grid(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{grid_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::imshow(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{imshow_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::legend(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{legend_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::plot(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{plot_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::quiver(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{quiver_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::scatter(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{scatter_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::savefig(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{savefig_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::show(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{show_attr(*args, **kwargs)}; +} + +axes::Axes PyPlot::subplot(const pybind11::dict & kwargs) +{ + return axes::Axes(subplot_attr(**kwargs)); +} + +axes::Axes PyPlot::subplot(int cri) +{ + return axes::Axes(subplot_attr(cri)); +} + +std::tuple PyPlot::subplots(const pybind11::dict & kwargs) +{ + pybind11::list ret = subplots_attr(**kwargs); + pybind11::object fig = ret[0]; + pybind11::object ax = ret[1]; + return {figure::Figure(fig), axes::Axes(ax)}; +} + +std::tuple> PyPlot::subplots( + int r, int c, const pybind11::dict & kwargs) +{ + // subplots() returns [][] (if r > 1 && c > 1) else [] + // return []axes in row-major + // NOTE: equal to Axes.flat + pybind11::tuple args = pybind11::make_tuple(r, c); + pybind11::list ret = subplots_attr(*args, **kwargs); + std::vector axes; + pybind11::object fig = ret[0]; + figure::Figure figure(fig); + if (r == 1 && c == 1) { + // python returns Axes + axes.emplace_back(ret[1]); + } else if (r == 1 || c == 1) { + // python returns []Axes + pybind11::list axs = ret[1]; + for (int i = 0; i < r * c; ++i) axes.emplace_back(axs[i]); + } else { + // python returns [][]Axes + pybind11::list axs = ret[1]; + for (pybind11::size_t i = 0; i < axs.size(); ++i) { + pybind11::list ax_i = axs[i]; + for (unsigned j = 0; j < ax_i.size(); ++j) axes.emplace_back(ax_i[j]); + } + } + return {figure, axes}; +} + +PyObjectWrapper PyPlot::title(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{title_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::xlabel(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{xlabel_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::xlim(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{xlim_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::ylabel(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{ylabel_attr(*args, **kwargs)}; +} + +PyObjectWrapper PyPlot::ylim(const pybind11::tuple & args, const pybind11::dict & kwargs) +{ + return PyObjectWrapper{ylim_attr(*args, **kwargs)}; +} + +PyPlot import() +{ + auto mod = pybind11::module::import("matplotlib.pyplot"); + auto g_pyplot = PyPlot(mod); + return g_pyplot; +} + +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/quiver.cpp b/common/autoware_pyplot/src/quiver.cpp new file mode 100644 index 0000000000000..72614fb6227a7 --- /dev/null +++ b/common/autoware_pyplot/src/quiver.cpp @@ -0,0 +1,28 @@ +// 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 + +namespace autoware::pyplot +{ +inline namespace quiver +{ +Quiver::Quiver(const pybind11::object & object) : PyObjectWrapper(object) +{ +} +Quiver::Quiver(pybind11::object && object) : PyObjectWrapper(object) +{ +} +} // namespace quiver +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/src/text.cpp b/common/autoware_pyplot/src/text.cpp new file mode 100644 index 0000000000000..024c7c2daf946 --- /dev/null +++ b/common/autoware_pyplot/src/text.cpp @@ -0,0 +1,35 @@ +// 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::pyplot +{ +inline namespace text +{ +Text::Text(const pybind11::object & object) : PyObjectWrapper(object) +{ +} + +Text::Text(pybind11::object && object) : PyObjectWrapper(object) +{ +} + +void Text::load_attrs() +{ + LOAD_FUNC_ATTR(set_rotation, self_); +} +} // namespace text +} // namespace autoware::pyplot diff --git a/common/autoware_pyplot/test/test_pyplot.cpp b/common/autoware_pyplot/test/test_pyplot.cpp new file mode 100644 index 0000000000000..2055709c61f52 --- /dev/null +++ b/common/autoware_pyplot/test/test_pyplot.cpp @@ -0,0 +1,64 @@ +// 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 + +#include +#include +/* + very weirdly, you must include to pass vector. Although the code + compiles without it, the executable crashes at runtime + */ +#include + +#include + +TEST(PyPlot, single_plot) +{ + // NOTE: somehow, running multiple tests simultaneously causes the python interpreter to crash + py::scoped_interpreter guard{}; + auto plt = autoware::pyplot::import(); + { + plt.plot(Args(std::vector({1, 3, 2, 4})), Kwargs("color"_a = "blue", "linewidth"_a = 1.0)); + plt.xlabel(Args("x-title")); + plt.ylabel(Args("y-title")); + plt.title(Args("title")); + plt.xlim(Args(0, 5)); + plt.ylim(Args(0, 5)); + plt.grid(Args(true)); + plt.savefig(Args("test_single_plot.png")); + } + { + auto [fig, axes] = plt.subplots(1, 2); + auto & ax1 = axes[0]; + auto & ax2 = axes[1]; + + auto c = + autoware::pyplot::Circle(Args(py::make_tuple(0, 0), 0.5), Kwargs("fc"_a = "g", "ec"_a = "r")); + ax1.add_patch(Args(c.unwrap())); + + auto e = autoware::pyplot::Ellipse( + Args(py::make_tuple(-0.25, 0), 0.5, 0.25), Kwargs("fc"_a = "b", "ec"_a = "y")); + ax1.add_patch(Args(e.unwrap())); + + auto r = autoware::pyplot::Rectangle( + Args(py::make_tuple(0, 0), 0.25, 0.5), Kwargs("ec"_a = "#000000", "fill"_a = false)); + ax2.add_patch(Args(r.unwrap())); + + ax1.set_aspect(Args("equal")); + ax2.set_aspect(Args("equal")); + plt.savefig(Args("test_double_plot.svg")); + } +} From 536c805783651aebddb4f7f8ce780f7370deb9ca Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Mon, 25 Nov 2024 14:00:33 +0900 Subject: [PATCH 098/273] feat(autonomous_emergency_braking): set a lateral deviation limit for AEB IMU path (#9410) * add a steer limit option for AEB Signed-off-by: Daniel Sanchez * wip refactor and add max lat dev param Signed-off-by: Daniel Sanchez * fix issue with test Signed-off-by: Daniel Sanchez * delete unwanted parts Signed-off-by: Daniel Sanchez * delete unwanted changes Signed-off-by: Daniel Sanchez * set to false Signed-off-by: Daniel Sanchez * change back path length Signed-off-by: Daniel Sanchez * add suggestions Signed-off-by: Daniel Sanchez * update readme Signed-off-by: Daniel Sanchez * cpp check Signed-off-by: Daniel Sanchez * fix some sentences Signed-off-by: Daniel Sanchez * expand explanation Signed-off-by: Daniel Sanchez * update image Signed-off-by: Daniel Sanchez * update README Signed-off-by: Daniel Sanchez * update description Signed-off-by: Daniel Sanchez * fix typo Signed-off-by: Daniel Sanchez * fix sentences Signed-off-by: Daniel Sanchez * improve readme Signed-off-by: Daniel Sanchez --------- Signed-off-by: Daniel Sanchez --- .../README.md | 52 +- .../autonomous_emergency_braking.param.yaml | 18 +- .../image/labeling.drawio.svg | 390 ++++++++++ .../measuring-lat-dev-on-imu-path.drawio.svg | 374 +++++++++ .../image/obstacle_filtering_1.drawio.svg | 708 +++++++++++------- .../image/rss_check.drawio.svg | 223 ++++-- .../speed_calculation_expansion.drawio.svg | 184 +++-- .../autonomous_emergency_braking/node.hpp | 3 +- .../src/node.cpp | 63 +- .../test/test.cpp | 2 +- 10 files changed, 1553 insertions(+), 464 deletions(-) create mode 100644 control/autoware_autonomous_emergency_braking/image/labeling.drawio.svg create mode 100644 control/autoware_autonomous_emergency_braking/image/measuring-lat-dev-on-imu-path.drawio.svg diff --git a/control/autoware_autonomous_emergency_braking/README.md b/control/autoware_autonomous_emergency_braking/README.md index 42b3f4c9f96de..f0f4a6c9f7014 100644 --- a/control/autoware_autonomous_emergency_braking/README.md +++ b/control/autoware_autonomous_emergency_braking/README.md @@ -60,6 +60,8 @@ We do not activate AEB module if it satisfies the following conditions. ### 2. Generate a predicted path of the ego vehicle +#### IMU path generation + AEB generates a predicted footprint path based on current velocity and current angular velocity obtained from attached sensors. Note that if `use_imu_path` is `false`, it skips this step. This predicted path is generated as: $$ @@ -68,9 +70,21 @@ y_{k+1} = y_k + v sin(\theta_k) dt \\ \theta_{k+1} = \theta_k + \omega dt $$ -where $v$ and $\omega$ are current longitudinal velocity and angular velocity respectively. $dt$ is time interval that users can define in advance. +where $v$ and $\omega$ are current longitudinal velocity and angular velocity respectively. $dt$ is time interval that users can define in advance with the `imu_prediction_time_interval` parameter. The IMU path is generated considering a time horizon, defined by the `imu_prediction_time_horizon` parameter. + +Since the IMU path generation only uses the ego vehicle's current angular velocity, disregarding the MPC's planner steering, the shape of the IMU path tends to get distorted quite easily and protrude out of the ego vehicle's current lane, possibly causing unwanted emergency stops. That is why it is not recommended to use a big `imu_prediction_time_horizon`. To fix this issue, the IMU path's length can be cut short by tuning the `max_generated_imu_path_length` parameter, the IMU path generation will be cut short once its length surpasses this parameter's value. + +It is also possible to limit the IMU path length based on the predicted lateral deviation of the vehicle by setting the `limit_imu_path_lat_dev` parameter flag to "true", and setting a threshold lateral deviation with the `imu_path_lat_dev_threshold` parameter. That way, the AEB will generate a predicted IMU path until a given predicted ego pose surpasses the lateral deviation threshold, and the IMU path will be cut short when the ego vehicle is turning relatively fast. + +The advantage of setting a lateral deviation limit with the `limit_imu_path_lat_dev` parameter is that the `imu_prediction_time_horizon` and the `max_generated_imu_path_length` can be increased without worries about the IMU predicted path deforming beyond a certain threshold. The downside is that the IMU path will be cut short when the ego has a high angular velocity, in said cases, the AEB module would mostly rely on the MPC path to prevent or mitigate collisions. If it is assumed the ego vehicle will mostly travel along the centerline of its lanelets, it can be useful to set the lateral deviation threshold parameter `imu_path_lat_dev_threshold` to be equal to or smaller than the average lanelet width divided by 2, that way, the chance of the IMU predicted path leaving the current ego lanelet is smaller, and it is possible to increase the `imu_prediction_time_horizon` to prevent frontal collisions when the ego is mostly traveling in a straight line. + +The lateral deviation is measured using the ego vehicle's current position as a reference, and it measures the distance of the furthermost vertex of the predicted ego footprint to the predicted path. The following image illustrates how the lateral deviation of a given ego pose is measured. + +![measuring_lat_dev](./image/measuring-lat-dev-on-imu-path.drawio.svg) + +#### MPC path generation -On the other hand, if `use_predicted_trajectory` is set to true, the AEB module will use the predicted path from the MPC as a base to generate a footprint path. Both the IMU footprint path and the MPC footprint path can be used at the same time. +If the `use_predicted_trajectory` parameter is set to true, the AEB module will directly use the predicted path from the MPC as a base to generate a footprint path. It will copy the ego poses generated by the MPC until a given time horizon. The `mpc_prediction_time_horizon` parameter dictates how far ahead in the future the MPC path will predict the ego vehicle's movement. Both the IMU footprint path and the MPC footprint path can be used at the same time. ### 3. Get target obstacles @@ -82,7 +96,7 @@ The AEB module can filter the input pointcloud to find target obstacles with whi ##### Rough filtering -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 rough filtering step 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 plus the `expand_width` parameter) away from the predicted path of the ego vehicle and ignore the point cloud that are not within it. The rough filtering step is illustrated below. ![rough_filtering](./image/obstacle_filtering_1.drawio.svg) @@ -94,26 +108,34 @@ Furthermore, a 2D convex hull is created around each detected cluster, the verti ##### Rigorous filtering -After Noise filtering, the module 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. +After Noise filtering, the module 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 labeled as target obstacles. ![rigorous_filtering](./image/obstacle_filtering_2.drawio.svg) +##### Obstacle labeling + +After rigorous filtering, the remaining obstacles are labeled. An obstacle is given a "target" label for collision checking only if it falls within the ego vehicle's defined footprint (made using the ego vehicle's width and the `expand_width` parameter). For an emergency stop to occur, at least one obstacle needs to be labeled as a target. + +![labeling](./image/labeling.drawio.svg) + #### Using predicted objects to get target obstacles -If the `use_predicted_object_data` parameter is set to true, the AEB can use predicted object data coming from the perception modules, to get target obstacle points. This is done by obtaining the 2D intersection points between the ego's predicted footprint path and each of the predicted objects enveloping polygon or bounding box. +If the `use_predicted_object_data` parameter is set to true, the AEB can use predicted object data coming from the perception modules, to get target obstacle points. This is done by obtaining the 2D intersection points between the ego's predicted footprint path (made using the ego vehicle's width and the `expand_width` parameter) and each of the predicted objects enveloping polygon or bounding box. if there is no intersection, all points are discarded. ![predicted_object_and_path_intersection](./image/using-predicted-objects.drawio.svg) ### Finding the closest target obstacle -Once all target obstacles have been identified, the AEB module chooses the point that is closest to the ego vehicle as the candidate for collision checking. Only the closest point is considered because RSS distance is used to judge if a collision will happen or not, and if the closest vertex to the ego is deemed to be safe from collision, the rest of the target obstacles will also be safe. +After identifying all possible obstacles using pointcloud data and/or predicted object data, the AEB module selects the closest point to the ego vehicle as the candidate for collision checking. The "closest object" is defined as an obstacle within the ego vehicle's footprint, determined by its width and the `expand_width` parameter, that is closest to the ego vehicle along the longitudinal axis, using the IMU or MPC path as a reference. Target obstacles are prioritized over those outside the ego path, even if the latter are longitudinally closer. This prioritization ensures that the collision check focuses on objects that pose the highest risk based on the vehicle's trajectory. + +If no target obstacles are found, the AEB module considers other nearby obstacles outside the path. In such cases, it skips the collision check but records the position of the closest obstacle to calculate its speed (Step #4). Note that, obstacles obtained with predicted object data are all target obstacles since they are within the ego footprint path and it is not necessary to calculate their speed (it is already calculated by the perception module). Such obstacles are excluded from step #4. ![closest_object](./image/closest-point.drawio.svg) ### 4. Obstacle velocity estimation To begin calculating the target point's velocity, the point must enter the speed calculation area, -which is defined by the `speed_calculation_expansion_margin` parameter. +which is defined by the `speed_calculation_expansion_margin` parameter plus the ego vehicles width and the `expand_width` parameter. Depending on the operational environment, this margin can reduce unnecessary autonomous emergency braking caused by velocity miscalculations during the initial calculation steps. @@ -148,19 +170,24 @@ $$ where $yaw_{diff}$ is the difference in yaw between the ego path and the displacement vector $$v_{pos} = o_{pos} - prev_{pos} $$ and $v_{ego}$ is the ego's current speed, which accounts for the movement of points caused by the ego moving and not the object. All these equations are performed disregarding the z axis (in 2D). -Note that, the object velocity is calculated against the ego's current movement direction. If the object moves in the opposite direction to the ego's movement, the object velocity will be negative, which will reduce the rss distance on the next step. +Note that the object velocity is calculated against the ego's current movement direction. If the object moves in the opposite direction to the ego's movement, the object velocity will be negative, which will reduce the rss distance on the next step. The resulting estimated object speed is added to a queue of speeds with timestamps. The AEB then checks for expiration of past speed estimations and eliminates expired speed measurements from the queue, the object expiration is determined by checking if the time elapsed since the speed was first added to the queue is larger than the parameter `previous_obstacle_keep_time`. Finally, the median speed of the queue is calculated. The median speed will be used to calculate the RSS distance used for collision checking. ### 5. Collision check with target obstacles using RSS distance -In the fourth step, it checks the collision with the closest obstacle point using RSS distance. RSS distance is formulated as: +In the fifth step, the AEB module checks for collision with the closest target obstacle using RSS distance. +Only the closest target object is evaluated because RSS distance is used to determine collision risk. If the nearest target point is deemed safe, all other potential obstacles within the path are also assumed to be safe. + +RSS distance is formulated as: $$ d = v_{ego}*t_{response} + v_{ego}^2/(2*a_{min}) -(sign(v_{obj})) * v_{obj}^2/(2*a_{obj_{min}}) + offset $$ -where $v_{ego}$ and $v_{obj}$ is current ego and obstacle velocity, $a_{min}$ and $a_{obj_{min}}$ is ego and object minimum acceleration (maximum deceleration), $t_{response}$ is response time of the ego vehicle to start deceleration. Therefore the distance from the ego vehicle to the obstacle is smaller than this RSS distance $d$, the ego vehicle send emergency stop signals. This is illustrated in the following picture. +where $v_{ego}$ and $v_{obj}$ is current ego and obstacle velocity, $a_{min}$ and $a_{obj_{min}}$ is ego and object minimum acceleration (maximum deceleration), $t_{response}$ is response time of the ego vehicle to start deceleration. Therefore the distance from the ego vehicle to the obstacle is smaller than this RSS distance $d$, the ego vehicle send emergency stop signals. + +Only obstacles classified as "targets" (as defined in Step #3) are considered for RSS distance calculations. Among these "target" obstacles, the one closest to the ego vehicle is used for the calculation. If no "target" obstacles are present—meaning no obstacles fall within the ego vehicle's predicted path (determined by its width and an expanded margin)—this step is skipped. Instead, the position of the closest obstacle is recorded for future speed calculations (Step #4). In this scenario, no emergency stop diagnostic message is generated. The process is illustrated in the accompanying diagram. ![rss_check](./image/rss_check.drawio.svg) @@ -215,7 +242,7 @@ When vehicle odometry information is faulty, it is possible that the MPC fails t | maximum_cluster_size | [-] | int | maximum amount of points contained by a cluster for it to be considered as a possible target obstacle | 10000 | | min_generated_imu_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 | | max_generated_imu_path_length | [m] | double | maximum distance for a predicted path generated by sensors | 10.0 | -| expand_width | [m] | double | expansion width of the ego vehicle for the collision check | 0.1 | +| expand_width | [m] | double | expansion width of the ego vehicle for collision checking, path cropping and speed calculation | 0.1 | | longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 | | t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 | | a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 | @@ -225,7 +252,8 @@ When vehicle odometry information is faulty, it is possible that the MPC fails t | mpc_prediction_time_horizon | [s] | double | time horizon of the predicted path generated by mpc | 1.5 | | mpc_prediction_time_interval | [s] | double | time interval of the predicted path generated by mpc | 0.1 | | aeb_hz | [-] | double | frequency at which AEB operates per second | 10 | -| speed_calculation_expansion_margin | [m] | double | expansion width of the ego vehicle for the beginning speed calculation | 0.1 | +| speed_calculation_expansion_margin | [m] | double | expansion width of the ego vehicle footprint used when calculating the closest object's speed | 0.7 | +| path_footprint_extra_margin | [m] | double | this parameters expands the ego footprint used to crop the AEB input pointcloud | 1.0 | ## Limitations 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 f7548536beaef..99ca4d4ef52cb 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 @@ -3,10 +3,12 @@ # Ego path calculation use_predicted_trajectory: true use_imu_path: true + limit_imu_path_lat_dev: false use_pointcloud_data: true use_predicted_object_data: false use_object_velocity_calculation: true check_autoware_state: true + imu_path_lat_dev_threshold: 1.75 min_generated_imu_path_length: 0.5 max_generated_imu_path_length: 10.0 imu_prediction_time_horizon: 1.5 @@ -21,14 +23,14 @@ # Point cloud partitioning detection_range_min_height: 0.0 detection_range_max_height_margin: 0.0 - voxel_grid_x: 0.05 - voxel_grid_y: 0.05 - voxel_grid_z: 100000.0 + voxel_grid_x: 0.1 + voxel_grid_y: 0.1 + voxel_grid_z: 0.5 # Point cloud cropping - expand_width: 0.1 - path_footprint_extra_margin: 4.0 - speed_calculation_expansion_margin: 0.5 + expand_width: -0.2 + path_footprint_extra_margin: 1.0 + speed_calculation_expansion_margin: 0.7 # Point cloud clustering cluster_tolerance: 0.15 #[m] @@ -37,10 +39,10 @@ maximum_cluster_size: 10000 # RSS distance collision check - longitudinal_offset: 2.0 + longitudinal_offset: 1.0 t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 - collision_keeping_sec: 2.0 + collision_keeping_sec: 3.0 previous_obstacle_keep_time: 1.0 aeb_hz: 10.0 diff --git a/control/autoware_autonomous_emergency_braking/image/labeling.drawio.svg b/control/autoware_autonomous_emergency_braking/image/labeling.drawio.svg new file mode 100644 index 0000000000000..0f9995a9918cd --- /dev/null +++ b/control/autoware_autonomous_emergency_braking/image/labeling.drawio.svg @@ -0,0 +1,390 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Labeling target obstacles +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ expand_width + speed_calculation_expansion_margin + ego width / 2 +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + +
+
+
+ Target obstacles +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ expand_width  + ego width / 2 +
+
+
+
+ +
+
+
+
+
+ + + + + +
+
+
+
Regular obstacles (used only for speed calculation)
+
+
+
+
+ +
+
+
+
+ + + + + +
+
+
+
diff --git a/control/autoware_autonomous_emergency_braking/image/measuring-lat-dev-on-imu-path.drawio.svg b/control/autoware_autonomous_emergency_braking/image/measuring-lat-dev-on-imu-path.drawio.svg new file mode 100644 index 0000000000000..9dbd85f28207e --- /dev/null +++ b/control/autoware_autonomous_emergency_braking/image/measuring-lat-dev-on-imu-path.drawio.svg @@ -0,0 +1,374 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Y +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ lat dev +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ lat threshold +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + +
+
+
+ X +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ lat dev +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + + + + + + + + + + +
+
+
+ IMU path is cut the before lateral deviation threshold is exceeded +
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg b/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg index ee5ec62fbc1d4..48f7659c36d8d 100644 --- a/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg +++ b/control/autoware_autonomous_emergency_braking/image/obstacle_filtering_1.drawio.svg @@ -5,296 +5,436 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="595px" - height="534px" - viewBox="-0.5 -0.5 595 534" - content="<mxfile host="app.diagrams.net" modified="2024-06-13T07:18:04.299Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/121.0.0.0 Safari/537.36" etag="hdT1j-Hjagtqen0Xp5w0" version="24.5.4" type="google" scale="1" border="0"> <diagram name="Page-1" id="eIJewT680QnBEBDdotri"> <mxGraphModel dx="1364" dy="940" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="8Dxr__kcSdhv2497bxnN-1" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB2aWV3Qm94PSIwIDAgMTE5LjQ2IDQwIiBpZD0iTGF5ZXJfMiI+PGRlZnM+PHN0eWxlPi5jbHMtMXtjbGlwLXBhdGg6dXJsKCNjbGlwcGF0aCk7fS5jbHMtMntmaWxsOm5vbmU7fS5jbHMtMiwuY2xzLTN7c3Ryb2tlLXdpZHRoOjBweDt9LmNscy0ze2ZpbGw6IzIzMWYyMDt9PC9zdHlsZT48Y2xpcFBhdGggaWQ9ImNsaXBwYXRoIj48cmVjdCBoZWlnaHQ9IjQwIiB3aWR0aD0iMTE1LjExIiB4PSIuNSIgY2xhc3M9ImNscy0yIi8+PC9jbGlwUGF0aD48L2RlZnM+PGcgaWQ9IlJvYWRzIj48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9Ii41IiBjbGFzcz0iY2xzLTMiLz48cGF0aCBkPSJtMTA0LjksMjAuNWgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFaIiBjbGFzcz0iY2xzLTMiLz48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9IjExMi4xMSIgY2xhc3M9ImNscy0zIi8+PGcgY2xhc3M9ImNscy0xIj48cG9seWdvbiBwb2ludHM9IjAgMi41OSAwIDMuNTIgMS4wMiAzLjUyIDEuMDIgMy41OSAxMTguNDYgMy41OSAxMTguNDYgMzYuNDEgMSAzNi40MSAxIDM2LjQgMCAzNi40IDAgMzcuNDEgMTE5LjQ2IDM3LjQxIDExOS40NiAyLjU5IDAgMi41OSIgY2xhc3M9ImNscy0zIi8+PC9nPjwvZz48L3N2Zz4=;" vertex="1" parent="1"> <mxGeometry x="180" y="50" width="595" height="200" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-2" value="" style="group;opacity=30;" vertex="1" connectable="0" parent="1"> <mxGeometry x="340" y="325" width="420" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-3" value="" style="group;fillColor=#dae8fc;strokeColor=#6c8ebf;container=0;" vertex="1" connectable="0" parent="8Dxr__kcSdhv2497bxnN-2"> <mxGeometry width="420" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-4" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-2"> <mxGeometry x="280" width="140" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-5" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-2"> <mxGeometry x="140" width="140" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-6" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-2"> <mxGeometry width="140" height="155" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-7" value="" style="group" vertex="1" connectable="0" parent="1"> <mxGeometry x="340" y="370" width="420" height="85" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-8" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-7"> <mxGeometry x="280" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-9" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-7"> <mxGeometry x="140" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-10" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8Dxr__kcSdhv2497bxnN-7"> <mxGeometry width="140" height="60" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-11" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="1"> <mxGeometry relative="1" as="geometry"> <mxPoint x="350.0000000000002" y="109.48676906857327" as="sourcePoint" /> <mxPoint x="456.7649999999999" y="109.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-12" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="466.34" y="87" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-13" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="464" y="103" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-14" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="468.34000000000003" y="117" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-15" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="480" y="87" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-16" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="488" y="125" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-17" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="472" y="97" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-18" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB2aWV3Qm94PSIwIDAgMTE5LjQ2IDQwIiBpZD0iTGF5ZXJfMiI+PGRlZnM+PHN0eWxlPi5jbHMtMXtjbGlwLXBhdGg6dXJsKCNjbGlwcGF0aCk7fS5jbHMtMntmaWxsOm5vbmU7fS5jbHMtMiwuY2xzLTN7c3Ryb2tlLXdpZHRoOjBweDt9LmNscy0ze2ZpbGw6IzIzMWYyMDt9PC9zdHlsZT48Y2xpcFBhdGggaWQ9ImNsaXBwYXRoIj48cmVjdCBoZWlnaHQ9IjQwIiB3aWR0aD0iMTE1LjExIiB4PSIuNSIgY2xhc3M9ImNscy0yIi8+PC9jbGlwUGF0aD48L2RlZnM+PGcgaWQ9IlJvYWRzIj48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9Ii41IiBjbGFzcz0iY2xzLTMiLz48cGF0aCBkPSJtMTA0LjksMjAuNWgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFaIiBjbGFzcz0iY2xzLTMiLz48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9IjExMi4xMSIgY2xhc3M9ImNscy0zIi8+PGcgY2xhc3M9ImNscy0xIj48cG9seWdvbiBwb2ludHM9IjAgMi41OSAwIDMuNTIgMS4wMiAzLjUyIDEuMDIgMy41OSAxMTguNDYgMy41OSAxMTguNDYgMzYuNDEgMSAzNi40MSAxIDM2LjQgMCAzNi40IDAgMzcuNDEgMTE5LjQ2IDM3LjQxIDExOS40NiAyLjU5IDAgMi41OSIgY2xhc3M9ImNscy0zIi8+PC9nPjwvZz48L3N2Zz4=;" vertex="1" parent="1"> <mxGeometry x="180" y="341" width="595" height="200" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-19" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="1"> <mxGeometry relative="1" as="geometry"> <mxPoint x="456.7649999999999" y="400.5" as="targetPoint" /> <mxPoint x="350.0000000000002" y="400.48676906857327" as="sourcePoint" /> </mxGeometry> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-20" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="466.34" y="378" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-21" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="464" y="394" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-22" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="468.34000000000003" y="408" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-23" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="480" y="378" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-24" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="488" y="416" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-25" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="472" y="388" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-26" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/png,iVBORw0KGgoAAAANSUhEUgAAAKwAAABKCAYAAAAmLL9HAAAACXBIWXMAADT9AAA1CgHHClLTAAAJN0lEQVR4nO2dQW7bOBSGfxezLJDMbnbJADWjXdwTVD1B3BNEPcGkJxjNCeKeYJQT1DlBlBPU2QlEgbF33U0MdJ9Z8KmRnkhTylgSJfMDhIC2adHML/LxkXycPD09oQmBEHMAIYAZXUeNvsBz6GwBrOhKMymXTTJP6gg2EOIUQAxgDi9Qz37ZAlgCiDMp17YP7xRsIMQxlFD/2FPhPJ5dfIYS7qPpA0bBBkLMoJR/0k7ZPB4tGwDzTMqV7k2tYAMhIgAL6Lv/vAlPAaxMX+wpEwhRquhMyklfZekTaghnUOMgk4m5BXCVSZnwNyqCJbH+bfiSBYDFribbo8cLtgqZnFd06YT7kYu2JFhSf6rJfAsg8kJ9OV6wZki4CYAL9tYWQFjsxX8KljKtULVZbzIpo7YKeyh4wdoJhEgAXLKXNwBmeWP5S+GNGAMUK/UKIYBj+jsIAiHSvsvQEo8o+1lr98qZlFEgBFAW7QmUyRAD1MKSn/Uflv82k3L+8nK3RyBECCCC9wsPgVsAS90AykQgxBJV8+D3TMr1K0rE7M0tlCCcIhAiCoRYA7iDegq9WN3nAsDfgRBrmiWtQwSlwSIxAOSC5V/klCcgEGIWCLGC8l54v/AwOQHwJRBiSeMlI6S9BXt5DgCTs+l0DuBL4Y0tgFNXBBsIcQXg2vKxeyjvxpqutnkD5Ut8DeA3umycs/TDvgvVAt/p+gFlk36rkafoZzU1Lg9QXiejD59EvUa5F/0wOZtOFyhPvToz0DKMGnPuASRNbKP/WZYQ3m7OJ42STMrU9mGqsxjAO8N3hRbRJij//z9PzqbTlH1hxVnbBzSK1v3Qe6j55rSjcsyguiddWQ6Ze6jZKOtMJwk3QbXFLbmsNPkilCex7l9BNd9Fep9qpSdLJ5BPmZRhh2JdAPhqKMuh8w7AV6qjndD/a4aqGXQC1WKb4FqcTc6mU6cc2oEQMYA/2cvW7mPPZTiGsom53Vkkt5tzv+MYCQt/dz20D1D/H+u4x9Bzfsqk1AqfT7g4JVjqOu7Yyy6JdQNlky1dGZR2BdXLHPoJJqCmaA31axzoc8G+4h/omYSlXRHrFsq2P82kTA5NrIByNdFvPwXwEVU/6TmAtKbLKmIvH0HNZllxRrBkCvAnt5ZRv0cW0LufZi4MRF2B6kJnk56j6j/V5V8BuGEvR3Xu7YRgC8vMitx2KRKaheEutLybW3dVjqFAdRKiKtrLmjNaMUufkEdmJ04IFnrfZq0uYo/wliE3Rw6u+68L1U2IqnlQp5VdQ60zKGIVuiuC5eK86bJVI38fN0fmXqx2qI640E6oTm2kLB3aMvQuWFopxu1G6xO6Z2KWvunK1zsGqK64TRrXyMrHJ6e2DL0LFtWn6qHLgRbZTbx1jbu6/4iIWdpqk2oaBevCJhcFm3Z8f96dPfhBVnOozvgAbO/rqV0Q7ClLpx3fn7cCScf3HxMJS1tH/U1xQbD8R607vv8pS491mrULGtukTfnF/pHWKbmzeohzwAd8Tgu2sMwxxLPNt4HqmWot+2sRXne71mK8CBdaWKdw1ZUVCHFMe53y7UHFAcoJvXZXZ0V/W3RRd16wA6CwxoFvzNNxgRpz+kPFC3YYJGjWvZ5jpINHL1jHIZuVt6wbqNVjEwC/Qq2e2rDPXFDeUeEF6z4RS+fbShLgedkflLeFi5bnHTxesO4TsrQ2fiq9FlvyDh4vWPfh05XGPVCa5Ziji+HgBTswdrmOxuoZKOIF6z4lu9SybI/P3XObdvB4wbpPytKxriUtnEexK+/gcWFq1rObBNXwkyvaA5fbs6bdrEm7Rese38I6Dq0N4FtJTqAiovxLly5I3u0YF6F7wQ6DCM2Cxz1ghD5YwAt2EBQ2+/GWVsctRrx50tuwAyHf7Of48sLW8YIdGCTItOdi9IY3CRiH4Hxviy7qzgXBloIw1In+sWf4YKbr+48JXnd7jzLugmBb3wdkYc3SXrAvp/X9eS4Ids3SYcf35w9M1PH9x0TE0nvfH+eCYFOWDju+P1/9dE7RaDwNMETw2RVd+0W4KNjzLu1Y2qXLF4nEXd1/RMQsvbHtgNbsiLAu1uldsIaIIV1HLoxZ+nKM20vaguqKhyqNa2RtbPP2LliCB3+77LJbpoXP/Onubbv0kKA64l3/pmZs35ClU1sGVwS7xAtijO4Z3qofYcTbpfdBYft549i+1CDxzZVWm9cJwRqOaryoGWN0X2VYohoyMo/bf9pVOYYC1UmK6kDrhurSRszSVpsXcESwAJBJGaPaLS86nki4gj5u/4qOEPXg53GqK+jPg6jTus5QtXmTOvd2RrBExNJ5t9yJaAurorhojwBc04nU0SGaCRQqKT9N/RpVM6DJsUcJe3mLmiagU+d0AYM8WA4Y72KUGYBjOHaw3CPKT8vbHiIIlthxKLLxh7VUjgXKB0d7qnzOpKxjBpgagftMytCQZwZ1dGrO9hU053nWLmpL0Gni95q3rgMh0q58pPSPeGsoy6FzD9W41RFrCL3Nu8HuKN1ciyudYENbAbqAnjo+agdUd3JHwo06KMeKyvKeysPdb4fEFqoO3tMh1daZLDIB7lDdc7aF/aSekKVXk7PpdA7gC/si7bmffUAj0mvLx3J7co1uIni/gXr6XwP4jS4buhG163yn6wdUw/atRp4ZXSHMkWceAES7BE8mxBplc/XD5OnpCYEQ3I79i9xMTkC2TIIWIjp7OucWSqw2b0KM8uB7m0l5nLu1uKP3yiXXDXXLM+jDSnqGwQbAh0xK64F9hqNcl8CzHzZmbx7BwSAMhdOkvT05HG7xfBJ63eWGCap+3hgAJk9Pys1lcOHc0IjdWchcCPHsL3QV7nscq+fhEcreXQFIm46FDC7Nn66zomCP6SbcUHZetEOAO8D7nqBxEYNY8wDOj0BharZwyC3vZi/7PJnEM34KJ+RwsVZcX6W1BORm0DmCLwCsAyG0kfM8npdAQo2h3Fe6E3KuuOvrp0nAviiCWozADV9AqX4J5fdc9T2NOxS8SaCgMUc+7pjDrLEr3SJwrWALX7zECMOOe5xmA2UGaBtC4/JCyjAD8Lmlgnk8nL+gBljGXtvYwhah1eUxzE24x/NSchMzpg2pO6kl2CKBEHMo+yO3RbyAPU3YouynbRS74D+7OeKwBtsqIwAAAABJRU5ErkJggg==;direction=west;imageBackground=default;rotation=0;" vertex="1" parent="1"> <mxGeometry x="227.47000000000003" y="80.5" width="123.19" height="53" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-27" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/png,iVBORw0KGgoAAAANSUhEUgAAAKwAAABKCAYAAAAmLL9HAAAACXBIWXMAADT9AAA1CgHHClLTAAAJN0lEQVR4nO2dQW7bOBSGfxezLJDMbnbJADWjXdwTVD1B3BNEPcGkJxjNCeKeYJQT1DlBlBPU2QlEgbF33U0MdJ9Z8KmRnkhTylgSJfMDhIC2adHML/LxkXycPD09oQmBEHMAIYAZXUeNvsBz6GwBrOhKMymXTTJP6gg2EOIUQAxgDi9Qz37ZAlgCiDMp17YP7xRsIMQxlFD/2FPhPJ5dfIYS7qPpA0bBBkLMoJR/0k7ZPB4tGwDzTMqV7k2tYAMhIgAL6Lv/vAlPAaxMX+wpEwhRquhMyklfZekTaghnUOMgk4m5BXCVSZnwNyqCJbH+bfiSBYDFribbo8cLtgqZnFd06YT7kYu2JFhSf6rJfAsg8kJ9OV6wZki4CYAL9tYWQFjsxX8KljKtULVZbzIpo7YKeyh4wdoJhEgAXLKXNwBmeWP5S+GNGAMUK/UKIYBj+jsIAiHSvsvQEo8o+1lr98qZlFEgBFAW7QmUyRAD1MKSn/Uflv82k3L+8nK3RyBECCCC9wsPgVsAS90AykQgxBJV8+D3TMr1K0rE7M0tlCCcIhAiCoRYA7iDegq9WN3nAsDfgRBrmiWtQwSlwSIxAOSC5V/klCcgEGIWCLGC8l54v/AwOQHwJRBiSeMlI6S9BXt5DgCTs+l0DuBL4Y0tgFNXBBsIcQXg2vKxeyjvxpqutnkD5Ut8DeA3umycs/TDvgvVAt/p+gFlk36rkafoZzU1Lg9QXiejD59EvUa5F/0wOZtOFyhPvToz0DKMGnPuASRNbKP/WZYQ3m7OJ42STMrU9mGqsxjAO8N3hRbRJij//z9PzqbTlH1hxVnbBzSK1v3Qe6j55rSjcsyguiddWQ6Ze6jZKOtMJwk3QbXFLbmsNPkilCex7l9BNd9Fep9qpSdLJ5BPmZRhh2JdAPhqKMuh8w7AV6qjndD/a4aqGXQC1WKb4FqcTc6mU6cc2oEQMYA/2cvW7mPPZTiGsom53Vkkt5tzv+MYCQt/dz20D1D/H+u4x9Bzfsqk1AqfT7g4JVjqOu7Yyy6JdQNlky1dGZR2BdXLHPoJJqCmaA31axzoc8G+4h/omYSlXRHrFsq2P82kTA5NrIByNdFvPwXwEVU/6TmAtKbLKmIvH0HNZllxRrBkCvAnt5ZRv0cW0LufZi4MRF2B6kJnk56j6j/V5V8BuGEvR3Xu7YRgC8vMitx2KRKaheEutLybW3dVjqFAdRKiKtrLmjNaMUufkEdmJ04IFnrfZq0uYo/wliE3Rw6u+68L1U2IqnlQp5VdQ60zKGIVuiuC5eK86bJVI38fN0fmXqx2qI640E6oTm2kLB3aMvQuWFopxu1G6xO6Z2KWvunK1zsGqK64TRrXyMrHJ6e2DL0LFtWn6qHLgRbZTbx1jbu6/4iIWdpqk2oaBevCJhcFm3Z8f96dPfhBVnOozvgAbO/rqV0Q7ClLpx3fn7cCScf3HxMJS1tH/U1xQbD8R607vv8pS491mrULGtukTfnF/pHWKbmzeohzwAd8Tgu2sMwxxLPNt4HqmWot+2sRXne71mK8CBdaWKdw1ZUVCHFMe53y7UHFAcoJvXZXZ0V/W3RRd16wA6CwxoFvzNNxgRpz+kPFC3YYJGjWvZ5jpINHL1jHIZuVt6wbqNVjEwC/Qq2e2rDPXFDeUeEF6z4RS+fbShLgedkflLeFi5bnHTxesO4TsrQ2fiq9FlvyDh4vWPfh05XGPVCa5Ziji+HgBTswdrmOxuoZKOIF6z4lu9SybI/P3XObdvB4wbpPytKxriUtnEexK+/gcWFq1rObBNXwkyvaA5fbs6bdrEm7Rese38I6Dq0N4FtJTqAiovxLly5I3u0YF6F7wQ6DCM2Cxz1ghD5YwAt2EBQ2+/GWVsctRrx50tuwAyHf7Of48sLW8YIdGCTItOdi9IY3CRiH4Hxviy7qzgXBloIw1In+sWf4YKbr+48JXnd7jzLugmBb3wdkYc3SXrAvp/X9eS4Ids3SYcf35w9M1PH9x0TE0nvfH+eCYFOWDju+P1/9dE7RaDwNMETw2RVd+0W4KNjzLu1Y2qXLF4nEXd1/RMQsvbHtgNbsiLAu1uldsIaIIV1HLoxZ+nKM20vaguqKhyqNa2RtbPP2LliCB3+77LJbpoXP/Onubbv0kKA64l3/pmZs35ClU1sGVwS7xAtijO4Z3qofYcTbpfdBYft549i+1CDxzZVWm9cJwRqOaryoGWN0X2VYohoyMo/bf9pVOYYC1UmK6kDrhurSRszSVpsXcESwAJBJGaPaLS86nki4gj5u/4qOEPXg53GqK+jPg6jTus5QtXmTOvd2RrBExNJ5t9yJaAurorhojwBc04nU0SGaCRQqKT9N/RpVM6DJsUcJe3mLmiagU+d0AYM8WA4Y72KUGYBjOHaw3CPKT8vbHiIIlthxKLLxh7VUjgXKB0d7qnzOpKxjBpgagftMytCQZwZ1dGrO9hU053nWLmpL0Gni95q3rgMh0q58pPSPeGsoy6FzD9W41RFrCL3Nu8HuKN1ciyudYENbAbqAnjo+agdUd3JHwo06KMeKyvKeysPdb4fEFqoO3tMh1daZLDIB7lDdc7aF/aSekKVXk7PpdA7gC/si7bmffUAj0mvLx3J7co1uIni/gXr6XwP4jS4buhG163yn6wdUw/atRp4ZXSHMkWceAES7BE8mxBplc/XD5OnpCYEQ3I79i9xMTkC2TIIWIjp7OucWSqw2b0KM8uB7m0l5nLu1uKP3yiXXDXXLM+jDSnqGwQbAh0xK64F9hqNcl8CzHzZmbx7BwSAMhdOkvT05HG7xfBJ63eWGCap+3hgAJk9Pys1lcOHc0IjdWchcCPHsL3QV7nscq+fhEcreXQFIm46FDC7Nn66zomCP6SbcUHZetEOAO8D7nqBxEYNY8wDOj0BharZwyC3vZi/7PJnEM34KJ+RwsVZcX6W1BORm0DmCLwCsAyG0kfM8npdAQo2h3Fe6E3KuuOvrp0nAviiCWozADV9AqX4J5fdc9T2NOxS8SaCgMUc+7pjDrLEr3SJwrWALX7zECMOOe5xmA2UGaBtC4/JCyjAD8Lmlgnk8nL+gBljGXtvYwhah1eUxzE24x/NSchMzpg2pO6kl2CKBEHMo+yO3RbyAPU3YouynbRS74D+7OeKwBtsqIwAAAABJRU5ErkJggg==;direction=west;imageBackground=default;rotation=0;" vertex="1" parent="1"> <mxGeometry x="235.47000000000003" y="374.5" width="123.19" height="53" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-28" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="388.66999999999996" y="515" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-29" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;imageBorder=none;" vertex="1" parent="1"> <mxGeometry x="380.66999999999996" y="223" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-30" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="391.66999999999996" y="217" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-31" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="401.66999999999996" y="227" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-32" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="380.66999999999996" y="259" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-33" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="391.66999999999996" y="243" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-34" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="402.66999999999996" y="267" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-35" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="482" y="105" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-36" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478.34000000000003" y="127" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-37" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478" y="115" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-38" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="482" y="396" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-39" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478.34000000000003" y="418" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-40" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="479" y="406" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-41" value="Original Point Cloud" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;fontSize=18;" vertex="1" parent="1"> <mxGeometry x="395" y="27" width="180" height="40" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-42" value="Cropping the Point Cloud with extended path" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;fontSize=18;" vertex="1" parent="1"> <mxGeometry x="288.84" y="285" width="380" height="40" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-43" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="533" y="396" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="8Dxr__kcSdhv2497bxnN-44" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="535" y="105" width="8" height="8" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " + width="599px" + height="538px" + viewBox="-0.5 -0.5 599 538" + content="<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/131.0.0.0 Safari/537.36" version="24.8.8" scale="1" border="2"> <diagram name="Page-1" id="RP9hk2Fyg7B3xuBx3AVI"> <mxGraphModel dx="1314" dy="738" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="850" pageHeight="1100" math="0" 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,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB2aWV3Qm94PSIwIDAgMTE5LjQ2IDQwIiBpZD0iTGF5ZXJfMiI+PGRlZnM+PHN0eWxlPi5jbHMtMXtjbGlwLXBhdGg6dXJsKCNjbGlwcGF0aCk7fS5jbHMtMntmaWxsOm5vbmU7fS5jbHMtMiwuY2xzLTN7c3Ryb2tlLXdpZHRoOjBweDt9LmNscy0ze2ZpbGw6IzIzMWYyMDt9PC9zdHlsZT48Y2xpcFBhdGggaWQ9ImNsaXBwYXRoIj48cmVjdCBoZWlnaHQ9IjQwIiB3aWR0aD0iMTE1LjExIiB4PSIuNSIgY2xhc3M9ImNscy0yIi8+PC9jbGlwUGF0aD48L2RlZnM+PGcgaWQ9IlJvYWRzIj48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9Ii41IiBjbGFzcz0iY2xzLTMiLz48cGF0aCBkPSJtMTA0LjksMjAuNWgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFaIiBjbGFzcz0iY2xzLTMiLz48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9IjExMi4xMSIgY2xhc3M9ImNscy0zIi8+PGcgY2xhc3M9ImNscy0xIj48cG9seWdvbiBwb2ludHM9IjAgMi41OSAwIDMuNTIgMS4wMiAzLjUyIDEuMDIgMy41OSAxMTguNDYgMy41OSAxMTguNDYgMzYuNDEgMSAzNi40MSAxIDM2LjQgMCAzNi40IDAgMzcuNDEgMTE5LjQ2IDM3LjQxIDExOS40NiAyLjU5IDAgMi41OSIgY2xhc3M9ImNscy0zIi8+PC9nPjwvZz48L3N2Zz4=;" vertex="1" parent="1"> <mxGeometry x="180" y="50" width="595" height="200" as="geometry" /> </mxCell> <mxCell id="3" value="" style="group;opacity=30;" connectable="0" vertex="1" parent="1"> <mxGeometry x="340" y="325" width="420" height="155" as="geometry" /> </mxCell> <mxCell id="4" value="" style="group;fillColor=#dae8fc;strokeColor=#6c8ebf;container=0;" connectable="0" vertex="1" parent="3"> <mxGeometry width="420" height="155" as="geometry" /> </mxCell> <mxCell id="5" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="3"> <mxGeometry x="280" width="140" height="155" as="geometry" /> </mxCell> <mxCell id="6" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="3"> <mxGeometry x="140" width="140" height="155" as="geometry" /> </mxCell> <mxCell id="7" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#dae8fc;strokeColor=#6c8ebf;opacity=40;strokeWidth=5;" vertex="1" parent="3"> <mxGeometry width="140" height="155" as="geometry" /> </mxCell> <mxCell id="8" value="" style="group" connectable="0" vertex="1" parent="1"> <mxGeometry x="340" y="370" width="420" height="85" as="geometry" /> </mxCell> <mxCell id="9" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8"> <mxGeometry x="280" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="10" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8"> <mxGeometry x="140" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="11" value="" style="rounded=0;whiteSpace=wrap;html=1;fillColor=#d5e8d4;strokeColor=#82b366;opacity=40;strokeWidth=5;" vertex="1" parent="8"> <mxGeometry width="140" height="60" as="geometry" /> </mxCell> <mxCell id="12" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="1"> <mxGeometry relative="1" as="geometry"> <mxPoint x="350.0000000000002" y="109.48676906857327" as="sourcePoint" /> <mxPoint x="456.7649999999999" y="109.5" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="13" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="466.34" y="87" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="14" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="464" y="103" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="15" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="468.34000000000003" y="117" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="16" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="480" y="87" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="17" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="488" y="125" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="18" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="472" y="97" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="19" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB2aWV3Qm94PSIwIDAgMTE5LjQ2IDQwIiBpZD0iTGF5ZXJfMiI+PGRlZnM+PHN0eWxlPi5jbHMtMXtjbGlwLXBhdGg6dXJsKCNjbGlwcGF0aCk7fS5jbHMtMntmaWxsOm5vbmU7fS5jbHMtMiwuY2xzLTN7c3Ryb2tlLXdpZHRoOjBweDt9LmNscy0ze2ZpbGw6IzIzMWYyMDt9PC9zdHlsZT48Y2xpcFBhdGggaWQ9ImNsaXBwYXRoIj48cmVjdCBoZWlnaHQ9IjQwIiB3aWR0aD0iMTE1LjExIiB4PSIuNSIgY2xhc3M9ImNscy0yIi8+PC9jbGlwUGF0aD48L2RlZnM+PGcgaWQ9IlJvYWRzIj48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9Ii41IiBjbGFzcz0iY2xzLTMiLz48cGF0aCBkPSJtMTA0LjksMjAuNWgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFabS0xNC40MSwwaC03LjIxdi0xaDcuMjF2MVptLTE0LjQxLDBoLTcuMjF2LTFoNy4yMXYxWm0tMTQuNDEsMGgtNy4yMXYtMWg3LjIxdjFaIiBjbGFzcz0iY2xzLTMiLz48cmVjdCBoZWlnaHQ9IjEiIHdpZHRoPSIzLjUiIHk9IjE5LjUiIHg9IjExMi4xMSIgY2xhc3M9ImNscy0zIi8+PGcgY2xhc3M9ImNscy0xIj48cG9seWdvbiBwb2ludHM9IjAgMi41OSAwIDMuNTIgMS4wMiAzLjUyIDEuMDIgMy41OSAxMTguNDYgMy41OSAxMTguNDYgMzYuNDEgMSAzNi40MSAxIDM2LjQgMCAzNi40IDAgMzcuNDEgMTE5LjQ2IDM3LjQxIDExOS40NiAyLjU5IDAgMi41OSIgY2xhc3M9ImNscy0zIi8+PC9nPjwvZz48L3N2Zz4=;" vertex="1" parent="1"> <mxGeometry x="180" y="341" width="595" height="200" as="geometry" /> </mxCell> <mxCell id="20" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="1"> <mxGeometry relative="1" as="geometry"> <mxPoint x="456.7649999999999" y="400.5" as="targetPoint" /> <mxPoint x="350.0000000000002" y="400.48676906857327" as="sourcePoint" /> </mxGeometry> </mxCell> <mxCell id="21" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,PD94bWwgdmVyc2lvbj0iMS4wIiBlbmNvZGluZz0iVVRGLTgiIHN0YW5kYWxvbmU9Im5vIj8+CjwhLS0gQ3JlYXRlZCB3aXRoIElua3NjYXBlIChodHRwOi8vd3d3Lmlua3NjYXBlLm9yZy8pIC0tPgoKPHN2ZwogICB3aWR0aD0iNy4zMDU0NjA5bW0iCiAgIGhlaWdodD0iMy4xODI4MzIybW0iCiAgIHZpZXdCb3g9IjAgMCA3LjMwNTQ2MDkgMy4xODI4MzIyIgogICB2ZXJzaW9uPSIxLjEiCiAgIGlkPSJzdmcxIgogICB4bWw6c3BhY2U9InByZXNlcnZlIgogICBpbmtzY2FwZTp2ZXJzaW9uPSIxLjMgKDE6MS4zKzIwMjMwNzIzMTQ1OSswZTE1MGVkNmM0KSIKICAgc29kaXBvZGk6ZG9jbmFtZT0iYmVoYXZpb3JfcGF0aF9wbGFubmVyLnN2ZyIKICAgeG1sbnM6aW5rc2NhcGU9Imh0dHA6Ly93d3cuaW5rc2NhcGUub3JnL25hbWVzcGFjZXMvaW5rc2NhcGUiCiAgIHhtbG5zOnNvZGlwb2RpPSJodHRwOi8vc29kaXBvZGkuc291cmNlZm9yZ2UubmV0L0RURC9zb2RpcG9kaS0wLmR0ZCIKICAgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIgogICB4bWxuczpzdmc9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIj48c29kaXBvZGk6bmFtZWR2aWV3CiAgICAgaWQ9Im5hbWVkdmlldzEiCiAgICAgcGFnZWNvbG9yPSIjZmZmZmZmIgogICAgIGJvcmRlcmNvbG9yPSIjMDAwMDAwIgogICAgIGJvcmRlcm9wYWNpdHk9IjAuMjUiCiAgICAgaW5rc2NhcGU6c2hvd3BhZ2VzaGFkb3c9IjIiCiAgICAgaW5rc2NhcGU6cGFnZW9wYWNpdHk9IjAuMCIKICAgICBpbmtzY2FwZTpwYWdlY2hlY2tlcmJvYXJkPSIwIgogICAgIGlua3NjYXBlOmRlc2tjb2xvcj0iI2QxZDFkMSIKICAgICBpbmtzY2FwZTpkb2N1bWVudC11bml0cz0ibW0iCiAgICAgaW5rc2NhcGU6em9vbT0iMTkuMTA5NTAxIgogICAgIGlua3NjYXBlOmN4PSIxNzkuODMyMDEiCiAgICAgaW5rc2NhcGU6Y3k9IjQ4MC40NDE2MyIKICAgICBpbmtzY2FwZTp3aW5kb3ctd2lkdGg9IjM3NzAiCiAgICAgaW5rc2NhcGU6d2luZG93LWhlaWdodD0iMjA5NiIKICAgICBpbmtzY2FwZTp3aW5kb3cteD0iNzAiCiAgICAgaW5rc2NhcGU6d2luZG93LXk9IjI3IgogICAgIGlua3NjYXBlOndpbmRvdy1tYXhpbWl6ZWQ9IjEiCiAgICAgaW5rc2NhcGU6Y3VycmVudC1sYXllcj0ibGF5ZXIxIiAvPjxkZWZzCiAgICAgaWQ9ImRlZnMxIiAvPjxnCiAgICAgaW5rc2NhcGU6bGFiZWw9IkxheWVyIDEiCiAgICAgaW5rc2NhcGU6Z3JvdXBtb2RlPSJsYXllciIKICAgICBpZD0ibGF5ZXIxIgogICAgIHRyYW5zZm9ybT0idHJhbnNsYXRlKC01MS4zMjMzMjMsLTEzMi4wNTM0MikiPjxyZWN0CiAgICAgICBzdHlsZT0iZmlsbDojZjhjZWNjO2ZpbGwtb3BhY2l0eToxO3N0cm9rZTojMDAwMDAwO3N0cm9rZS13aWR0aDowLjE1O3N0cm9rZS1kYXNoYXJyYXk6bm9uZSIKICAgICAgIGlkPSJyZWN0MSIKICAgICAgIHdpZHRoPSI3LjE1NTQ2MzciCiAgICAgICBoZWlnaHQ9IjMuMDMyODMxNCIKICAgICAgIHg9IjUxLjM5ODMyMyIKICAgICAgIHk9IjEzMi4xMjg0MiIKICAgICAgIHJ5PSIwLjkzNTU2ODM5IiAvPjxwYXRoCiAgICAgICBpZD0icGF0aDkiCiAgICAgICBzdHlsZT0iZmlsbDojZjhjZWNjO2ZpbGwtb3BhY2l0eToxO3N0cm9rZTojMDAwMDAwO3N0cm9rZS13aWR0aDowLjE1O3N0cm9rZS1kYXNoYXJyYXk6bm9uZSIKICAgICAgIGQ9Im0gNTYuNjM1MjgyLDEzNC43OTk4NCAtMS4xNDEzNjUsLTAuMjQ1NSBtIDEuMTQxMzY1LC0yLjA1ODEgLTEuMTQxMzY1LDAuMjQ1NSBtIC0yLjYzNzE1NiwyLjA4NDY3IDEuMjM4Mzg3LC0wLjI5ODYzIG0gLTEuMjM4Mzg3LC0yLjA1ODExIDEuMjM4Mzg3LDAuMjk4NjQgbSAwLjczOTM5MSwxLjc3MDY4IHYgMC4zNTcyNyBtIDAsLTIuNDkzOTYgdiAwLjM1NzI3IG0gLTAuNzgyMjUxLC0wLjAxNDEgaCAxLjQ1ODQwMSB2IDEuODA3ODkgaCAtMS40NTg0MDEgeiBtIC0wLjg0MDE1NCwtMC4zMzA4MyBoIDIuOTE2Mzk4IGMgMC41ODkwMTksMCAxLjA2MzIxMiwwLjMzOTM5IDEuMDYzMjEyLDAuNzYwOTYgdiAwLjk0NDg4IGMgMCwwLjQyMTU3IC0wLjQ3NDE5MywwLjc2MDk2IC0xLjA2MzIxMiwwLjc2MDk2IGggLTIuOTE2Mzk4IGMgLTAuNTg5MDE5LDAgLTEuMDYzMjEyLC0wLjMzOTM5IC0xLjA2MzIxMiwtMC43NjA5NiB2IC0wLjk0NDg4IGMgMCwtMC40MjE1NyAwLjQ3NDE5MywtMC43NjA5NiAxLjA2MzIxMiwtMC43NjA5NiB6IiAvPjwvZz48L3N2Zz4K;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="466.34" y="378" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="22" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="464" y="394" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="23" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="468.34000000000003" y="408" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="24" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="480" y="378" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="25" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="488" y="416" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="26" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="472" y="388" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="27" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/png,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;direction=west;imageBackground=default;rotation=0;" vertex="1" parent="1"> <mxGeometry x="227.47000000000003" y="80.5" width="123.19" height="53" as="geometry" /> </mxCell> <mxCell id="28" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/png,iVBORw0KGgoAAAANSUhEUgAAAKwAAABKCAYAAAAmLL9HAAAACXBIWXMAADT9AAA1CgHHClLTAAAJN0lEQVR4nO2dQW7bOBSGfxezLJDMbnbJADWjXdwTVD1B3BNEPcGkJxjNCeKeYJQT1DlBlBPU2QlEgbF33U0MdJ9Z8KmRnkhTylgSJfMDhIC2adHML/LxkXycPD09oQmBEHMAIYAZXUeNvsBz6GwBrOhKMymXTTJP6gg2EOIUQAxgDi9Qz37ZAlgCiDMp17YP7xRsIMQxlFD/2FPhPJ5dfIYS7qPpA0bBBkLMoJR/0k7ZPB4tGwDzTMqV7k2tYAMhIgAL6Lv/vAlPAaxMX+wpEwhRquhMyklfZekTaghnUOMgk4m5BXCVSZnwNyqCJbH+bfiSBYDFribbo8cLtgqZnFd06YT7kYu2JFhSf6rJfAsg8kJ9OV6wZki4CYAL9tYWQFjsxX8KljKtULVZbzIpo7YKeyh4wdoJhEgAXLKXNwBmeWP5S+GNGAMUK/UKIYBj+jsIAiHSvsvQEo8o+1lr98qZlFEgBFAW7QmUyRAD1MKSn/Uflv82k3L+8nK3RyBECCCC9wsPgVsAS90AykQgxBJV8+D3TMr1K0rE7M0tlCCcIhAiCoRYA7iDegq9WN3nAsDfgRBrmiWtQwSlwSIxAOSC5V/klCcgEGIWCLGC8l54v/AwOQHwJRBiSeMlI6S9BXt5DgCTs+l0DuBL4Y0tgFNXBBsIcQXg2vKxeyjvxpqutnkD5Ut8DeA3umycs/TDvgvVAt/p+gFlk36rkafoZzU1Lg9QXiejD59EvUa5F/0wOZtOFyhPvToz0DKMGnPuASRNbKP/WZYQ3m7OJ42STMrU9mGqsxjAO8N3hRbRJij//z9PzqbTlH1hxVnbBzSK1v3Qe6j55rSjcsyguiddWQ6Ze6jZKOtMJwk3QbXFLbmsNPkilCex7l9BNd9Fep9qpSdLJ5BPmZRhh2JdAPhqKMuh8w7AV6qjndD/a4aqGXQC1WKb4FqcTc6mU6cc2oEQMYA/2cvW7mPPZTiGsom53Vkkt5tzv+MYCQt/dz20D1D/H+u4x9Bzfsqk1AqfT7g4JVjqOu7Yyy6JdQNlky1dGZR2BdXLHPoJJqCmaA31axzoc8G+4h/omYSlXRHrFsq2P82kTA5NrIByNdFvPwXwEVU/6TmAtKbLKmIvH0HNZllxRrBkCvAnt5ZRv0cW0LufZi4MRF2B6kJnk56j6j/V5V8BuGEvR3Xu7YRgC8vMitx2KRKaheEutLybW3dVjqFAdRKiKtrLmjNaMUufkEdmJ04IFnrfZq0uYo/wliE3Rw6u+68L1U2IqnlQp5VdQ60zKGIVuiuC5eK86bJVI38fN0fmXqx2qI640E6oTm2kLB3aMvQuWFopxu1G6xO6Z2KWvunK1zsGqK64TRrXyMrHJ6e2DL0LFtWn6qHLgRbZTbx1jbu6/4iIWdpqk2oaBevCJhcFm3Z8f96dPfhBVnOozvgAbO/rqV0Q7ClLpx3fn7cCScf3HxMJS1tH/U1xQbD8R607vv8pS491mrULGtukTfnF/pHWKbmzeohzwAd8Tgu2sMwxxLPNt4HqmWot+2sRXne71mK8CBdaWKdw1ZUVCHFMe53y7UHFAcoJvXZXZ0V/W3RRd16wA6CwxoFvzNNxgRpz+kPFC3YYJGjWvZ5jpINHL1jHIZuVt6wbqNVjEwC/Qq2e2rDPXFDeUeEF6z4RS+fbShLgedkflLeFi5bnHTxesO4TsrQ2fiq9FlvyDh4vWPfh05XGPVCa5Ziji+HgBTswdrmOxuoZKOIF6z4lu9SybI/P3XObdvB4wbpPytKxriUtnEexK+/gcWFq1rObBNXwkyvaA5fbs6bdrEm7Rese38I6Dq0N4FtJTqAiovxLly5I3u0YF6F7wQ6DCM2Cxz1ghD5YwAt2EBQ2+/GWVsctRrx50tuwAyHf7Of48sLW8YIdGCTItOdi9IY3CRiH4Hxviy7qzgXBloIw1In+sWf4YKbr+48JXnd7jzLugmBb3wdkYc3SXrAvp/X9eS4Ids3SYcf35w9M1PH9x0TE0nvfH+eCYFOWDju+P1/9dE7RaDwNMETw2RVd+0W4KNjzLu1Y2qXLF4nEXd1/RMQsvbHtgNbsiLAu1uldsIaIIV1HLoxZ+nKM20vaguqKhyqNa2RtbPP2LliCB3+77LJbpoXP/Onubbv0kKA64l3/pmZs35ClU1sGVwS7xAtijO4Z3qofYcTbpfdBYft549i+1CDxzZVWm9cJwRqOaryoGWN0X2VYohoyMo/bf9pVOYYC1UmK6kDrhurSRszSVpsXcESwAJBJGaPaLS86nki4gj5u/4qOEPXg53GqK+jPg6jTus5QtXmTOvd2RrBExNJ5t9yJaAurorhojwBc04nU0SGaCRQqKT9N/RpVM6DJsUcJe3mLmiagU+d0AYM8WA4Y72KUGYBjOHaw3CPKT8vbHiIIlthxKLLxh7VUjgXKB0d7qnzOpKxjBpgagftMytCQZwZ1dGrO9hU053nWLmpL0Gni95q3rgMh0q58pPSPeGsoy6FzD9W41RFrCL3Nu8HuKN1ciyudYENbAbqAnjo+agdUd3JHwo06KMeKyvKeysPdb4fEFqoO3tMh1daZLDIB7lDdc7aF/aSekKVXk7PpdA7gC/si7bmffUAj0mvLx3J7co1uIni/gXr6XwP4jS4buhG163yn6wdUw/atRp4ZXSHMkWceAES7BE8mxBplc/XD5OnpCYEQ3I79i9xMTkC2TIIWIjp7OucWSqw2b0KM8uB7m0l5nLu1uKP3yiXXDXXLM+jDSnqGwQbAh0xK64F9hqNcl8CzHzZmbx7BwSAMhdOkvT05HG7xfBJ63eWGCap+3hgAJk9Pys1lcOHc0IjdWchcCPHsL3QV7nscq+fhEcreXQFIm46FDC7Nn66zomCP6SbcUHZetEOAO8D7nqBxEYNY8wDOj0BharZwyC3vZi/7PJnEM34KJ+RwsVZcX6W1BORm0DmCLwCsAyG0kfM8npdAQo2h3Fe6E3KuuOvrp0nAviiCWozADV9AqX4J5fdc9T2NOxS8SaCgMUc+7pjDrLEr3SJwrWALX7zECMOOe5xmA2UGaBtC4/JCyjAD8Lmlgnk8nL+gBljGXtvYwhah1eUxzE24x/NSchMzpg2pO6kl2CKBEHMo+yO3RbyAPU3YouynbRS74D+7OeKwBtsqIwAAAABJRU5ErkJggg==;direction=west;imageBackground=default;rotation=0;" vertex="1" parent="1"> <mxGeometry x="235.47000000000003" y="374.5" width="123.19" height="53" as="geometry" /> </mxCell> <mxCell id="29" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;" vertex="1" parent="1"> <mxGeometry x="388.66999999999996" y="515" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="30" value="" style="shape=image;aspect=fixed;image=data:image/svg+xml,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;points=[[0,0.25,0,0,0],[0,0.5,0,0,0],[0,0.75,0,0,0],[0.1,0,0,0,0],[0.1,1,0,0,0],[0.25,0,0,0,0],[0.25,1,0,0,0],[0.5,0,0,0,0],[0.5,1,0,0,0],[0.75,0,0,0,0],[0.75,1,0,0,0],[0.89,0,0,0,0],[0.89,1,0,0,0],[1,0.25,0,0,0],[1,0.5,0,0,0],[1,0.75,0,0,0]];imageBackground=none;imageAspect=0;perimeter=none;imageBorder=none;" vertex="1" parent="1"> <mxGeometry x="380.66999999999996" y="223" width="107.33" height="46" as="geometry" /> </mxCell> <mxCell id="31" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="391.66999999999996" y="217" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="32" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="401.66999999999996" y="227" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="33" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="380.66999999999996" y="259" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="34" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="391.66999999999996" y="243" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="35" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="402.66999999999996" y="267" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="36" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="482" y="105" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="37" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478.34000000000003" y="127" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="38" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478" y="115" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="39" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="482" y="396" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="40" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="478.34000000000003" y="418" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="41" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="479" y="406" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="42" value="Original Point Cloud" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;fontSize=18;" vertex="1" parent="1"> <mxGeometry x="395" y="27" width="180" height="40" as="geometry" /> </mxCell> <mxCell id="43" value="Cropping the Point Cloud with extended path" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;fontSize=18;" vertex="1" parent="1"> <mxGeometry x="288.84" y="285" width="380" height="40" as="geometry" /> </mxCell> <mxCell id="44" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="533" y="396" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="45" value="" style="ellipse;whiteSpace=wrap;html=1;aspect=fixed;fillColor=#e1d5e7;strokeColor=#9673a6;" vertex="1" parent="1"> <mxGeometry x="535" y="105" width="8" height="8" as="geometry" /> </mxCell> <mxCell id="46" value="" style="endArrow=classic;startArrow=classic;html=1;rounded=0;exitX=0.319;exitY=0.695;exitDx=0;exitDy=0;exitPerimeter=0;dashed=1;" edge="1" source="19" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="370" y="442" as="sourcePoint" /> <mxPoint x="370" y="402" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="47" value="expand_width +&amp;nbsp;path_footprint_extra_margin + Ego width / 2" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="46"> <mxGeometry x="-0.2514" y="1" relative="1" as="geometry"> <mxPoint x="164" y="49" as="offset" /> </mxGeometry> </mxCell> <mxCell id="48" value="" style="endArrow=classic;html=1;rounded=0;entryX=0.84;entryY=0.195;entryDx=0;entryDy=0;entryPerimeter=0;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="370.77" y="446" as="sourcePoint" /> <mxPoint x="420.56999999999994" y="496" as="targetPoint" /> </mxGeometry> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " style="background-color: rgb(255, 255, 255);" > - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-
-
Original Point Cloud
-
-
- - - - - - - - - - - - -
-
-
- Cropping the Point Cloud with extended path -
-
-
-
- -
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Original Point Cloud +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Cropping the Point Cloud with extended path +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + +
+
+
+ expand_width + path_footprint_extra_margin + Ego width / 2 +
+
+
+
+ +
+
+
+
+
+ + + + + +
- - - - - -
diff --git a/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg b/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg index 1d3dd824df5f0..82590ed107558 100644 --- a/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg +++ b/control/autoware_autonomous_emergency_braking/image/rss_check.drawio.svg @@ -1,73 +1,170 @@ + + + - - - - - - - - - - - - - - - - -
-
- - Closest point distance -
-
-
-
-
-
- - - - - - -
-
- RSS distance -
-
-
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + Closest point distance +
+
+
+
+
+
+ Closest point distance +
+
+
+
+
+ + + + + + + + + + + +
+
+
+ RSS distance +
+
+
+
+ RSS distance +
+
+
+
+
+ + + + + + + + + + +
+
+
+ ego vehicle width + 2 * expand_width +
+
+
+
+ ego vehicle width + 2 * expand_width +
+
+
+
+
+
+ + + + Text is not SVG - cannot display + +
diff --git a/control/autoware_autonomous_emergency_braking/image/speed_calculation_expansion.drawio.svg b/control/autoware_autonomous_emergency_braking/image/speed_calculation_expansion.drawio.svg index 37728253370e4..8df567f05962c 100644 --- a/control/autoware_autonomous_emergency_braking/image/speed_calculation_expansion.drawio.svg +++ b/control/autoware_autonomous_emergency_braking/image/speed_calculation_expansion.drawio.svg @@ -3,19 +3,15 @@ - - - + @@ -24,24 +20,24 @@ - +
-
-
+
+
speed_calculation_expansion_margin
@@ -51,19 +47,19 @@ + >#svg-image-FwhNqmDYWad8ta0ORfnb .cls-1 { clip-path: url("#clippath"); } #svg-image-FwhNqmDYWad8ta0ORfnb .cls-2 { fill: none; } #svg-image-FwhNqmDYWad8ta0ORfnb .cls-2, #svg-image-FwhNqmDYWad8ta0ORfnb .cls-3 { stroke-width: 0px; } #svg-image-FwhNqmDYWad8ta0ORfnb .cls-3 { fill: rgb(35, 31, 32); } @@ -87,147 +83,181 @@ - + - + - + - + - + - - + + - +
-
-
- speed_calculation_expansion_margin +
+
+ ego width / 2 + expand_width + speed_calculation_expansion_margin
- - - - - - - - - - - - - - - - - - - - - + + - +
-
-
- Closest Point +
+
+ Closest Point to ego
+ + + + + + + + + + + + + + + + + + + + + + + + + - + - + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 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 d18185c77335c..96efb5dc9ff1f 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 @@ -553,13 +553,14 @@ class AEB : public rclcpp::Node // Member variables bool publish_debug_pointcloud_; bool publish_debug_markers_; - bool publish_debug_time_; bool use_predicted_trajectory_; bool use_imu_path_; + bool limit_imu_path_lat_dev_; bool use_pointcloud_data_; bool use_predicted_object_data_; bool use_object_velocity_calculation_; bool check_autoware_state_; + double imu_path_lat_dev_threshold_; double path_footprint_extra_margin_; double speed_calculation_expansion_margin_; double detection_range_min_height_; diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 846a7654d7313..7c4cf58cbc6e7 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include @@ -154,11 +155,13 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) publish_debug_markers_ = declare_parameter("publish_debug_markers"); use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); use_imu_path_ = declare_parameter("use_imu_path"); + limit_imu_path_lat_dev_ = declare_parameter("limit_imu_path_lat_dev"); 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"); + imu_path_lat_dev_threshold_ = declare_parameter("imu_path_lat_dev_threshold"); speed_calculation_expansion_margin_ = declare_parameter("speed_calculation_expansion_margin"); detection_range_min_height_ = declare_parameter("detection_range_min_height"); @@ -216,12 +219,14 @@ rcl_interfaces::msg::SetParametersResult AEB::onParameter( updateParam(parameters, "publish_debug_markers", publish_debug_markers_); updateParam(parameters, "use_predicted_trajectory", use_predicted_trajectory_); updateParam(parameters, "use_imu_path", use_imu_path_); + updateParam(parameters, "limit_imu_path_lat_dev", limit_imu_path_lat_dev_); updateParam(parameters, "use_pointcloud_data", use_pointcloud_data_); 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, "imu_path_lat_dev_threshold", imu_path_lat_dev_threshold_); updateParam( parameters, "speed_calculation_expansion_margin", speed_calculation_expansion_margin_); updateParam(parameters, "detection_range_min_height", detection_range_min_height_); @@ -647,14 +652,6 @@ bool AEB::hasCollision(const double current_v, const ObjectData & closest_object Path AEB::generateEgoPath(const double curr_v, const double curr_w) { autoware::universe_utils::ScopedTimeTrack st(std::string(__func__) + "(IMU)", *time_keeper_); - Path path; - double curr_x = 0.0; - double curr_y = 0.0; - double curr_yaw = 0.0; - geometry_msgs::msg::Pose ini_pose; - ini_pose.position = autoware::universe_utils::createPoint(curr_x, curr_y, 0.0); - ini_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw); - path.push_back(ini_pose); const double & dt = imu_prediction_time_interval_; const double distance_between_points = std::abs(curr_v) * dt; constexpr double minimum_distance_between_points{1e-2}; @@ -662,28 +659,57 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w) // if distance between points is too small, arc length calculation is unreliable, so we skip // creating the path if (std::abs(curr_v) < 0.1 || distance_between_points < minimum_distance_between_points) { - return path; + return {}; } - const double & horizon = imu_prediction_time_horizon_; + // The initial pose is always aligned with the local reference frame. + geometry_msgs::msg::Pose initial_pose; + initial_pose.position = autoware::universe_utils::createPoint(0.0, 0.0, 0.0); + initial_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(0.0); + + const double horizon = imu_prediction_time_horizon_; + const double base_link_to_front_offset = vehicle_info_.max_longitudinal_offset_m; + const double rear_overhang = vehicle_info_.rear_overhang_m; + const double vehicle_half_width = expand_width_ + vehicle_info_.vehicle_width_m / 2.0; + + // Choose the coordinates of the ego footprint vertex that will used to check for lateral + // deviation + const auto longitudinal_offset = (curr_v > 0.0) ? base_link_to_front_offset : -rear_overhang; + const auto lateral_offset = (curr_v * curr_w > 0.0) ? vehicle_half_width : -vehicle_half_width; + + Path path{initial_pose}; + path.reserve(static_cast(horizon / dt)); + double curr_x = 0.0; + double curr_y = 0.0; + double curr_yaw = 0.0; double path_arc_length = 0.0; double t = 0.0; - bool finished_creating_path = false; - while (!finished_creating_path) { + while (true) { curr_x = curr_x + curr_v * std::cos(curr_yaw) * dt; curr_y = curr_y + curr_v * std::sin(curr_yaw) * dt; curr_yaw = curr_yaw + curr_w * dt; - geometry_msgs::msg::Pose current_pose; - current_pose.position = autoware::universe_utils::createPoint(curr_x, curr_y, 0.0); - current_pose.orientation = autoware::universe_utils::createQuaternionFromYaw(curr_yaw); + geometry_msgs::msg::Pose current_pose = + autoware::universe_utils::calcOffsetPose(initial_pose, curr_x, curr_y, 0.0, curr_yaw); t += dt; path_arc_length += distance_between_points; + const auto edge_of_ego_vehicle = autoware::universe_utils::calcOffsetPose( + current_pose, longitudinal_offset, lateral_offset, 0.0) + .position; + + const bool basic_path_conditions_satisfied = + (t > horizon) && (path_arc_length > min_generated_imu_path_length_); + const bool path_length_threshold_surpassed = path_arc_length > max_generated_imu_path_length_; + const bool lat_dev_threshold_surpassed = + limit_imu_path_lat_dev_ && std::abs(edge_of_ego_vehicle.y) > imu_path_lat_dev_threshold_; + + if ( + basic_path_conditions_satisfied || path_length_threshold_surpassed || + lat_dev_threshold_surpassed) { + break; + } - finished_creating_path = (t > horizon) && (path_arc_length > min_generated_imu_path_length_); - finished_creating_path = - (finished_creating_path) || (path_arc_length > max_generated_imu_path_length_); path.push_back(current_pose); } return path; @@ -826,6 +852,7 @@ void AEB::createObjectDataUsingPredictedObjects( obj.position = obj_position; obj.velocity = obj_tangent_velocity; obj.distance_to_object = std::abs(dist_ego_to_object); + obj.is_target = true; object_data_vector.push_back(obj); collision_points_added = true; } diff --git a/control/autoware_autonomous_emergency_braking/test/test.cpp b/control/autoware_autonomous_emergency_braking/test/test.cpp index c2a58941cc144..3c00a4e6b5caf 100644 --- a/control/autoware_autonomous_emergency_braking/test/test.cpp +++ b/control/autoware_autonomous_emergency_braking/test/test.cpp @@ -210,7 +210,7 @@ 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); + ASSERT_EQ(imu_path.size(), 0); } TEST_F(TestAEB, checkParamUpdate) From 341ea150c91735569d7eece0049eff27f15081cc Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 25 Nov 2024 14:29:27 +0900 Subject: [PATCH 099/273] fix(autoware_perception_rviz_plugin): fix orientation indication rendering fix (#9434) refactor: fix orientation indication rendering fix Signed-off-by: Taekjin LEE --- .../src/object_detection/object_polygon_detail.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) 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 04d07462e8695..5742e6b5d1872 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 @@ -728,10 +728,10 @@ void calc_2d_bounding_box_bottom_orientation_line_list( // front corner cuts for orientation const double point_list[4][3] = { - {length_half, width_half - tick_width, height_half}, - {length_half - tick_length, width_half, height_half}, - {length_half, -width_half + tick_width, height_half}, - {length_half - tick_length, -width_half, height_half}, + {length_half, width_half - tick_width, -height_half}, + {length_half - tick_length, width_half, -height_half}, + {length_half, -width_half + tick_width, -height_half}, + {length_half - tick_length, -width_half, -height_half}, }; const int point_pairs[2][2] = { {0, 1}, From 882af41502f936e4f7327ee9faeb210c2029d59d Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 25 Nov 2024 15:07:19 +0900 Subject: [PATCH 100/273] fix(goal_planner): remove stop reason (#9365) Signed-off-by: satoshi-ota --- .../src/goal_planner_module.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index b4fa4dfe30d7a..fed42be0753d7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -1489,8 +1489,6 @@ void GoalPlannerModule::postProcess() {distance_to_path_change.first, distance_to_path_change.second}, has_decided_path ? SteeringFactor::TURNING : SteeringFactor::APPROACHING); - setStopReason(StopReason::GOAL_PLANNER, pull_over_path.full_path()); - setVelocityFactor(pull_over_path.full_path()); context_data_ = std::nullopt; From badf8ca728f098735ded4f802b57e9e8011ee802 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 25 Nov 2024 15:09:25 +0900 Subject: [PATCH 101/273] fix(avoidance): remove stop reason (#9364) Signed-off-by: satoshi-ota --- .../src/scene.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index f0fc87648bc4a..f7fc4ee48d364 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -780,8 +780,6 @@ void StaticObstacleAvoidanceModule::updateEgoBehavior( insertReturnDeadLine(isBestEffort(parameters_->policy_deceleration), path); - setStopReason(StopReason::AVOIDANCE, path.path); - setVelocityFactor(path.path); } From 135de571b317e8c93110de429b2cac5f5d0650f9 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Mon, 25 Nov 2024 16:52:01 +0900 Subject: [PATCH 102/273] feat(planning_evaluator): add processing time pub (#9334) Signed-off-by: Kasunori-Nakajima --- .../planning_evaluator/planning_evaluator_node.hpp | 3 +++ .../src/planning_evaluator_node.cpp | 11 +++++++++++ 2 files changed, 14 insertions(+) diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp index 81787741a7583..065d168b02d38 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp @@ -23,6 +23,7 @@ #include #include +#include #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include "autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp" @@ -31,6 +32,7 @@ #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" #include +#include #include #include @@ -142,6 +144,7 @@ class PlanningEvaluatorNode : public rclcpp::Node autoware::universe_utils::InterProcessPollingSubscriber accel_sub_{ this, "~/input/acceleration"}; + rclcpp::Publisher::SharedPtr processing_time_pub_; rclcpp::Publisher::SharedPtr metrics_pub_; std::shared_ptr transform_listener_{nullptr}; std::unique_ptr tf_buffer_; diff --git a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp index a1d7c75891f4a..e5e1c947a735c 100644 --- a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp @@ -53,6 +53,9 @@ PlanningEvaluatorNode::PlanningEvaluatorNode(const rclcpp::NodeOptions & node_op output_file_str_ = declare_parameter("output_file"); ego_frame_str_ = declare_parameter("ego_frame"); + processing_time_pub_ = + this->create_publisher("~/debug/processing_time_ms", 1); + // List of metrics to calculate and publish metrics_pub_ = create_publisher("~/metrics", 1); for (const std::string & selected_metric : @@ -222,6 +225,8 @@ void PlanningEvaluatorNode::AddMetricMsg(const Metric & metric, const Stat stop_watch; + const auto ego_state_ptr = odometry_sub_.takeData(); onOdometry(ego_state_ptr); { @@ -247,6 +252,12 @@ void PlanningEvaluatorNode::onTimer() metrics_msg_.stamp = now(); metrics_pub_->publish(metrics_msg_); metrics_msg_ = MetricArrayMsg{}; + + // Publish ProcessingTime + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + processing_time_pub_->publish(processing_time_msg); } void PlanningEvaluatorNode::onTrajectory( From b782772ee0ab506b309002e4a49bc8acd3da9bb8 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Mon, 25 Nov 2024 17:01:37 +0900 Subject: [PATCH 103/273] feat(mission_planner): add processing time publisher (#9342) * feat(mission_planner): add processing time publisher Signed-off-by: Kasunori-Nakajima * delete extra line Signed-off-by: Kasunori-Nakajima * update: mission_planner, route_selector, service_utils. Signed-off-by: Kasunori-Nakajima * Revert "update: mission_planner, route_selector, service_utils." This reverts commit d460a633c04c166385963c5233c3845c661e595e. Signed-off-by: Kasunori-Nakajima * Update to show that exceptions are not handled Signed-off-by: Kasunori-Nakajima * feat(mission_planner,route_selector): add processing time publisher Signed-off-by: Kasunori-Nakajima --------- Signed-off-by: Kasunori-Nakajima Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> Co-authored-by: Kosuke Takeuchi --- .../src/mission_planner/mission_planner.cpp | 11 +++++++++++ .../src/mission_planner/mission_planner.hpp | 5 +++++ .../src/mission_planner/route_selector.cpp | 13 +++++++++++++ .../src/mission_planner/route_selector.hpp | 5 +++++ .../src/mission_planner/service_utils.hpp | 4 ++++ 5 files changed, 38 insertions(+) diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp index 2b54160a81038..467bc33d20a56 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp @@ -83,6 +83,17 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) data_check_timer_ = create_wall_timer(period, [this] { check_initialization(); }); logger_configure_ = std::make_unique(this); + pub_processing_time_ = + this->create_publisher("~/debug/processing_time_ms", 1); +} + +void MissionPlanner::publish_processing_time( + autoware::universe_utils::StopWatch stop_watch) +{ + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + pub_processing_time_->publish(processing_time_msg); } void MissionPlanner::publish_pose_log(const Pose & pose, const std::string & pose_type) diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp index 9342bc7840641..b0389c49bef33 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include @@ -29,6 +30,7 @@ #include #include #include +#include #include #include #include @@ -68,6 +70,8 @@ class MissionPlanner : public rclcpp::Node { public: explicit MissionPlanner(const rclcpp::NodeOptions & options); + void publish_processing_time( + autoware::universe_utils::StopWatch stop_watch); private: ArrivalChecker arrival_checker_; @@ -141,6 +145,7 @@ class MissionPlanner : public rclcpp::Node bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route); std::unique_ptr logger_configure_; + rclcpp::Publisher::SharedPtr pub_processing_time_; }; } // namespace autoware::mission_planner diff --git a/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp b/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp index bfc809b921d90..5ee565af00423 100644 --- a/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/route_selector.cpp @@ -136,6 +136,19 @@ RouteSelector::RouteSelector(const rclcpp::NodeOptions & options) initialized_ = false; mrm_operating_ = false; main_request_ = std::monostate{}; + + // Processing time + pub_processing_time_ = + this->create_publisher("~/debug/processing_time_ms", 1); +} + +void RouteSelector::publish_processing_time( + autoware::universe_utils::StopWatch stop_watch) +{ + tier4_debug_msgs::msg::Float64Stamped processing_time_msg; + processing_time_msg.stamp = get_clock()->now(); + processing_time_msg.data = stop_watch.toc(); + pub_processing_time_->publish(processing_time_msg); } void RouteSelector::on_state(const RouteState::ConstSharedPtr msg) diff --git a/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp b/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp index a3423d7fbf1bd..5c8f81aaf216e 100644 --- a/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/route_selector.hpp @@ -15,9 +15,11 @@ #ifndef MISSION_PLANNER__ROUTE_SELECTOR_HPP_ #define MISSION_PLANNER__ROUTE_SELECTOR_HPP_ +#include #include #include +#include #include #include #include @@ -64,6 +66,8 @@ class RouteSelector : public rclcpp::Node { public: explicit RouteSelector(const rclcpp::NodeOptions & options); + void publish_processing_time( + autoware::universe_utils::StopWatch stop_watch); private: using WaypointRequest = SetWaypointRoute::Request::SharedPtr; @@ -78,6 +82,7 @@ class RouteSelector : public rclcpp::Node rclcpp::Client::SharedPtr cli_set_lanelet_route_; rclcpp::Subscription::SharedPtr sub_state_; rclcpp::Subscription::SharedPtr sub_route_; + rclcpp::Publisher::SharedPtr pub_processing_time_; bool initialized_; bool mrm_operating_; diff --git a/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp b/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp index 6e942ead9b383..b12b5f635275c 100644 --- a/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp @@ -15,6 +15,8 @@ #ifndef MISSION_PLANNER__SERVICE_UTILS_HPP_ #define MISSION_PLANNER__SERVICE_UTILS_HPP_ +#include + #include #include @@ -57,11 +59,13 @@ template std::function handle_exception(void (T::*callback)(Req, Res), T * instance) { return [instance, callback](Req req, Res res) { + autoware::universe_utils::StopWatch stop_watch; try { (instance->*callback)(req, res); } catch (const ServiceException & error) { error.set(res->status); } + instance->publish_processing_time(stop_watch); }; } From 9efee7824ed0d7217a85e72c840bc34af198b8b3 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Mon, 25 Nov 2024 17:30:20 +0900 Subject: [PATCH 104/273] ci: use CodeBuild for clang-tidy-differential (#9451) Signed-off-by: Ryohsuke Mitsudome --- .github/workflows/build-and-test-differential.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index c824bb94b2a6c..871fc67499f48 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -75,7 +75,7 @@ jobs: clang-tidy-differential: needs: build-and-test-differential - runs-on: ubuntu-22.04 + runs-on: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large container: ghcr.io/autowarefoundation/autoware:universe-devel-cuda steps: - name: Set PR fetch depth From 9c6895b191163c20726828523b1282e5aed8566a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Mon, 25 Nov 2024 18:45:02 +0900 Subject: [PATCH 105/273] fix(bpp)!: remove stop reason (#9449) fix(bpp): remove stop reason Signed-off-by: satoshi-ota --- .../autoware_behavior_path_planner/README.md | 1 - .../behavior_path_planner_node.hpp | 3 -- .../behavior_path_planner/planner_manager.hpp | 32 ------------------- .../launch/behavior_path_planner.launch.xml | 1 - .../src/behavior_path_planner_node.cpp | 2 -- .../interface/scene_module_interface.hpp | 29 ----------------- .../src/interface/scene_module_interface.cpp | 2 -- 7 files changed, 70 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/README.md b/planning/behavior_path_planner/autoware_behavior_path_planner/README.md index b6282e39e3910..ab8d02dc83f92 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/README.md +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/README.md @@ -113,7 +113,6 @@ The Planner Manager's responsibilities include: | ~/output/turn_indicators_cmd | `autoware_vehicle_msgs::msg::TurnIndicatorsCommand` | turn indicators command. | `volatile` | | ~/output/hazard_lights_cmd | `autoware_vehicle_msgs::msg::HazardLightsCommand` | hazard lights command. | `volatile` | | ~/output/modified_goal | `autoware_planning_msgs::msg::PoseWithUuidStamped` | output modified goal commands. | `transient_local` | -| ~/output/stop_reasons | `tier4_planning_msgs::msg::StopReasonArray` | describe the reason for ego vehicle stop | `volatile` | | ~/output/reroute_availability | `tier4_planning_msgs::msg::RerouteAvailability` | the path the module is about to take. to be executed as soon as external approval is obtained. | `volatile` | ### Debug diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp index f0bd4486eb04a..ebe7c47e6fab2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/behavior_path_planner_node.hpp @@ -40,7 +40,6 @@ #include #include #include -#include #include #include @@ -71,7 +70,6 @@ using tier4_planning_msgs::msg::LateralOffset; using tier4_planning_msgs::msg::PathWithLaneId; using tier4_planning_msgs::msg::RerouteAvailability; using tier4_planning_msgs::msg::Scenario; -using tier4_planning_msgs::msg::StopReasonArray; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; @@ -122,7 +120,6 @@ class BehaviorPathPlannerNode : public rclcpp::Node rclcpp::Publisher::SharedPtr hazard_signal_publisher_; rclcpp::Publisher::SharedPtr bound_publisher_; rclcpp::Publisher::SharedPtr modified_goal_publisher_; - rclcpp::Publisher::SharedPtr stop_reason_publisher_; rclcpp::Publisher::SharedPtr reroute_availability_publisher_; rclcpp::Publisher::SharedPtr pub_steering_factors_; rclcpp::TimerBase::SharedPtr timer_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp index 0cb9c02ccbc4b..3bed1e6a88bd8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/include/autoware/behavior_path_planner/planner_manager.hpp @@ -26,7 +26,6 @@ #include #include -#include #include @@ -42,7 +41,6 @@ namespace autoware::behavior_path_planner using autoware::universe_utils::StopWatch; using tier4_planning_msgs::msg::PathWithLaneId; -using tier4_planning_msgs::msg::StopReasonArray; using SceneModulePtr = std::shared_ptr; using SceneModuleManagerPtr = std::shared_ptr; using DebugPublisher = autoware::universe_utils::DebugPublisher; @@ -484,36 +482,6 @@ class PlannerManager return ret; } - /** - * @brief aggregate launched module's stop reasons. - * @return stop reason array - */ - StopReasonArray getStopReasons() const - { - StopReasonArray stop_reason_array; - stop_reason_array.header.frame_id = "map"; - stop_reason_array.header.stamp = clock_.now(); - - const auto approved_module_ptrs = approved_modules(); - const auto candidate_module_ptrs = candidate_modules(); - - std::for_each(approved_module_ptrs.begin(), approved_module_ptrs.end(), [&](const auto & m) { - const auto reason = m->getStopReason(); - if (reason.reason != "") { - stop_reason_array.stop_reasons.push_back(m->getStopReason()); - } - }); - - std::for_each(candidate_module_ptrs.begin(), candidate_module_ptrs.end(), [&](const auto & m) { - const auto reason = m->getStopReason(); - if (reason.reason != "") { - stop_reason_array.stop_reasons.push_back(m->getStopReason()); - } - }); - - return stop_reason_array; - } - /** * @brief check if re-routable approved module is running(namely except for fixed_goal_planner * and dynamic_avoidance) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/launch/behavior_path_planner.launch.xml b/planning/behavior_path_planner/autoware_behavior_path_planner/launch/behavior_path_planner.launch.xml index 79c590363beb5..e088250219039 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/launch/behavior_path_planner.launch.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/launch/behavior_path_planner.launch.xml @@ -37,7 +37,6 @@ - diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp index a2fffa0bb7a63..7758ab530e88c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp @@ -51,7 +51,6 @@ BehaviorPathPlannerNode::BehaviorPathPlannerNode(const rclcpp::NodeOptions & nod const auto durable_qos = rclcpp::QoS(1).transient_local(); modified_goal_publisher_ = create_publisher("~/output/modified_goal", durable_qos); - stop_reason_publisher_ = create_publisher("~/output/stop_reasons", 1); pub_steering_factors_ = create_publisher("/planning/steering_factor/intersection", 1); reroute_availability_publisher_ = @@ -408,7 +407,6 @@ void BehaviorPathPlannerNode::run() publishSceneModuleDebugMsg(planner_manager_->getDebugMsg()); publishPathCandidate(planner_manager_->getSceneModuleManagers(), planner_data_); publishPathReference(planner_manager_->getSceneModuleManagers(), planner_data_); - stop_reason_publisher_->publish(planner_manager_->getStopReasons()); // publish modified goal only when it is updated if ( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index 5da5c9ccc6c15..9fc4113e87d9e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -39,9 +39,6 @@ #include #include #include -#include -#include -#include #include #include #include @@ -69,9 +66,6 @@ using autoware_adapi_v1_msgs::msg::SteeringFactor; using autoware_adapi_v1_msgs::msg::VelocityFactor; using tier4_planning_msgs::msg::AvoidanceDebugMsgArray; using tier4_planning_msgs::msg::PathWithLaneId; -using tier4_planning_msgs::msg::StopFactor; -using tier4_planning_msgs::msg::StopReason; -using tier4_planning_msgs::msg::StopReasonArray; using tier4_rtc_msgs::msg::State; using unique_identifier_msgs::msg::UUID; using visualization_msgs::msg::MarkerArray; @@ -192,8 +186,6 @@ class SceneModuleInterface reset_factor(); - stop_reason_ = StopReason(); - processOnExit(); } @@ -266,8 +258,6 @@ class SceneModuleInterface ModuleStatus getCurrentStatus() const { return current_state_; } - StopReason getStopReason() const { return stop_reason_; } - void reset_factor() { steering_factor_interface_.reset(); @@ -446,8 +436,6 @@ class SceneModuleInterface BehaviorModuleOutput previous_module_output_; - StopReason stop_reason_; - bool is_locked_new_module_launch_{false}; bool is_locked_output_path_{false}; @@ -580,23 +568,6 @@ class SceneModuleInterface path.points, getEgoPose(), slow_pose_.value(), VelocityFactor::APPROACHING, "slow down"); } - void setStopReason(const std::string & stop_reason, const PathWithLaneId & path) - { - stop_reason_.reason = stop_reason; - stop_reason_.stop_factors.clear(); - - if (!stop_pose_) { - stop_reason_.reason = ""; - return; - } - - StopFactor stop_factor; - stop_factor.stop_pose = stop_pose_.value(); - stop_factor.dist_to_stop_pose = autoware::motion_utils::calcSignedArcLength( - path.points, getEgoPosition(), stop_pose_.value().position); - stop_reason_.stop_factors.push_back(stop_factor); - } - void setDrivableLanes(const std::vector & drivable_lanes); BehaviorModuleOutput getPreviousModuleOutput() const { return previous_module_output_; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp index 580b9c73888b6..a6c480e130d7a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp @@ -26,8 +26,6 @@ void SceneModuleInterface::onEntry() { RCLCPP_DEBUG(getLogger(), "%s %s", name_.c_str(), __func__); - stop_reason_ = StopReason(); - processOnEntry(); } } // namespace autoware::behavior_path_planner From 685f1aa46bf791fdb3966d0793c2b6fd5c15344d Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 25 Nov 2024 20:23:19 +0900 Subject: [PATCH 106/273] fix(autoware_smart_mpc_trajectory_follower): fix clang-diagnostic-ignored-optimization-argument (#9437) Signed-off-by: veqcc --- control/autoware_smart_mpc_trajectory_follower/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/control/autoware_smart_mpc_trajectory_follower/CMakeLists.txt b/control/autoware_smart_mpc_trajectory_follower/CMakeLists.txt index b4b21bded9c73..37d7925cdf0a0 100644 --- a/control/autoware_smart_mpc_trajectory_follower/CMakeLists.txt +++ b/control/autoware_smart_mpc_trajectory_follower/CMakeLists.txt @@ -9,6 +9,8 @@ find_package(pybind11 REQUIRED) find_package(Eigen3 REQUIRED) autoware_package() +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-ignored-optimization-argument") + execute_process(COMMAND bash -c "pip3 install numba==0.58.1 --force-reinstall") execute_process(COMMAND bash -c "pip3 install GPy") From 9769a9e3c24a072b847760a4ba8a8aeb930bf76e Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 25 Nov 2024 22:43:19 +0900 Subject: [PATCH 107/273] test(bpp_common): add unit test for traffic light utils (#9441) * add test data for traffic light utils Signed-off-by: Go Sakayori * add unit test function Signed-off-by: Go Sakayori * fix style Signed-off-by: Go Sakayori * use test_utils::resolve_plg_share_uri for map path Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../CMakeLists.txt | 5 +- .../src/utils/traffic_light_utils.cpp | 2 +- .../test/test_traffic_light_utils.cpp | 174 +++++++++++ .../test/test_utils.cpp | 2 +- .../test_data/test_traffic_light.yaml | 285 ++++++++++++++++++ 5 files changed, 465 insertions(+), 3 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_traffic_light_utils.cpp create mode 100644 planning/behavior_path_planner/autoware_behavior_path_planner_common/test_data/test_traffic_light.yaml diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt index ac33966a1bf7c..35fa1584c4635 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt @@ -35,6 +35,7 @@ if(BUILD_TESTING) ament_add_ros_isolated_gmock(test_${PROJECT_NAME}_utilities test/test_utils.cpp test/test_path_utils.cpp + test/test_traffic_light_utils.cpp ) target_link_libraries(test_${PROJECT_NAME}_utilities @@ -93,4 +94,6 @@ if(BUILD_TESTING) ) endif() -ament_auto_package() +ament_auto_package(INSTALL_TO_SHARE + test_data +) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp index 19c9bbcf365a3..c31bddd921f99 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp @@ -130,7 +130,7 @@ bool isStoppedAtRedTrafficLightWithinDistance( return false; } - return (distance_to_red_traffic_light < distance_threshold); + return (distance_to_red_traffic_light.value() < distance_threshold); } bool isTrafficSignalStop( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_traffic_light_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_traffic_light_utils.cpp new file mode 100644 index 0000000000000..a5d77b96292f9 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_traffic_light_utils.cpp @@ -0,0 +1,174 @@ +// 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 "ament_index_cpp/get_package_share_directory.hpp" +#include "autoware/behavior_path_planner_common/data_manager.hpp" +#include "autoware/behavior_path_planner_common/utils/traffic_light_utils.hpp" +#include "autoware_test_utils/autoware_test_utils.hpp" +#include "autoware_test_utils/mock_data_parser.hpp" + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +using autoware::behavior_path_planner::PlannerData; +using autoware::behavior_path_planner::TrafficSignalStamped; +using autoware_perception_msgs::msg::TrafficLightGroupArray; +using autoware_planning_msgs::msg::LaneletRoute; +using geometry_msgs::msg::Pose; + +const double epsilon = 1e-06; + +class TrafficLightTest : public ::testing::Test +{ +protected: + void SetUp() override + { + planner_data_ = std::make_shared(); + const auto test_data_file = + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner_common") + + "/test_data/test_traffic_light.yaml"; + YAML::Node config = YAML::LoadFile(test_data_file); + + set_current_pose(config); + set_route_handler(config); + set_traffic_signal(config); + } + + void set_current_pose(YAML::Node config) + { + const auto self_odometry = + autoware::test_utils::parse(config["self_odometry"]); + planner_data_->self_odometry = std::make_shared(self_odometry); + } + + void set_route_handler(YAML::Node config) + { + const auto route = autoware::test_utils::parse(config["route"]); + const auto map_path = + autoware::test_utils::resolve_pkg_share_uri(config["map_path_uri"].as()); + if (!map_path.has_value()) return; + const auto intersection_map = autoware::test_utils::make_map_bin_msg(map_path.value()); + planner_data_->route_handler->setMap(intersection_map); + planner_data_->route_handler->setRoute(route); + + for (const auto & segment : route.segments) { + lanelets.push_back( + planner_data_->route_handler->getLaneletsFromId(segment.preferred_primitive.id)); + } + } + + void set_traffic_signal(YAML::Node config) + { + const auto traffic_light = + autoware::test_utils::parse(config["traffic_signal"]); + for (const auto & signal : traffic_light.traffic_light_groups) { + TrafficSignalStamped traffic_signal; + traffic_signal.stamp = rclcpp::Clock{RCL_ROS_TIME}.now(); + traffic_signal.signal = signal; + planner_data_->traffic_light_id_map[signal.traffic_light_group_id] = traffic_signal; + } + } + + void set_zero_velocity() + { + nav_msgs::msg::Odometry odometry; + odometry.pose.pose = planner_data_->self_odometry->pose.pose; + odometry.twist.twist.linear = autoware::universe_utils::createVector3(0.0, 0.0, 0.0); + planner_data_->self_odometry = std::make_shared(odometry); + } + + lanelet::ConstLanelets lanelets; + std::shared_ptr planner_data_; +}; + +TEST_F(TrafficLightTest, getDistanceToNextTrafficLight) +{ + using autoware::behavior_path_planner::utils::traffic_light::getDistanceToNextTrafficLight; + + { + const Pose pose = autoware::test_utils::createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); + const lanelet::ConstLanelets empty_lanelets; + EXPECT_DOUBLE_EQ( + getDistanceToNextTrafficLight(pose, empty_lanelets), std::numeric_limits::infinity()); + } + { + EXPECT_NEAR( + getDistanceToNextTrafficLight(planner_data_->self_odometry->pose.pose, lanelets), 117.1599371, + epsilon); + } +} + +TEST_F(TrafficLightTest, calcDistanceToRedTrafficLight) +{ + using autoware::behavior_path_planner::utils::traffic_light::calcDistanceToRedTrafficLight; + + { + const tier4_planning_msgs::msg::PathWithLaneId path; + const lanelet::ConstLanelets empty_lanelets; + EXPECT_FALSE(calcDistanceToRedTrafficLight(empty_lanelets, path, planner_data_).has_value()); + } + { + const auto path = planner_data_->route_handler->getCenterLinePath(lanelets, 0.0, 300.0); + const auto distance = calcDistanceToRedTrafficLight(lanelets, path, planner_data_); + ASSERT_TRUE(distance.has_value()); + EXPECT_NEAR(distance.value(), 117.1096960, epsilon); + } +} + +TEST_F(TrafficLightTest, isStoppedAtRedTrafficLightWithinDistance) +{ + using autoware::behavior_path_planner::utils::traffic_light:: + isStoppedAtRedTrafficLightWithinDistance; + const auto distance_threshold = 10.0; + const auto path = planner_data_->route_handler->getCenterLinePath(lanelets, 0.0, 300.0); + { + EXPECT_FALSE( + isStoppedAtRedTrafficLightWithinDistance(lanelets, path, planner_data_, distance_threshold)); + } + { + set_zero_velocity(); + EXPECT_FALSE( + isStoppedAtRedTrafficLightWithinDistance(lanelets, path, planner_data_, distance_threshold)); + } + { + set_zero_velocity(); + EXPECT_TRUE(isStoppedAtRedTrafficLightWithinDistance(lanelets, path, planner_data_)); + } +} + +TEST_F(TrafficLightTest, isTrafficSignalStop) +{ + using autoware::behavior_path_planner::utils::traffic_light::isTrafficSignalStop; + + { + const lanelet::ConstLanelets empty_lanelets; + EXPECT_FALSE(isTrafficSignalStop(empty_lanelets, planner_data_)); + } + { + EXPECT_TRUE(isTrafficSignalStop(lanelets, planner_data_)); + } +} diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp index 09c7561955801..4326cfdb8e6be 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp @@ -1,4 +1,4 @@ -// Copyright 2024 Tier IV, Inc. All rights reserved. +// Copyright 2024 TIER IV, Inc. 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. diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test_data/test_traffic_light.yaml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test_data/test_traffic_light.yaml new file mode 100644 index 0000000000000..10d40a15fdb5a --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test_data/test_traffic_light.yaml @@ -0,0 +1,285 @@ +# +# AUTO GENERATED by autoware_test_utils::topic_snapshot_saver +# format1: +# +# format_version: +# map_path_uri: package:/// +# fields(this is array) +# - name: +# type: either {Odometry | AccelWithCovarianceStamped | PredictedObjects | OperationModeState | LaneletRoute | TrafficLightGroupArray | TrackedObjects | TBD} +# topic: +# +format_version: 1 +map_path_uri: package://autoware_test_utils/test_map/intersection/lanelet2_map.osm +dynamic_object: + header: + stamp: + sec: 50 + nanosec: 334681087 + frame_id: map + objects: [] +traffic_signal: + stamp: + sec: 1732179380 + nanosec: 814263853 + traffic_light_groups: + - traffic_light_group_id: 3010757 + elements: + - color: 1 + shape: 1 + status: 2 + confidence: 1.00000 +route: + header: + stamp: + sec: 24 + nanosec: 685572149 + frame_id: map + start_pose: + position: + x: 363.790 + y: 433.627 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.695229 + w: 0.718789 + goal_pose: + position: + x: 356.900 + y: 863.677 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.715472 + w: 0.698641 + segments: + - preferred_primitive: + id: 1001 + primitive_type: "" + primitives: + - id: 1000 + primitive_type: lane + - id: 1001 + primitive_type: lane + - id: 1002 + primitive_type: lane + - id: 1003 + primitive_type: lane + - preferred_primitive: + id: 1011 + primitive_type: "" + primitives: + - id: 1010 + primitive_type: lane + - id: 1011 + primitive_type: lane + - id: 1012 + primitive_type: lane + - preferred_primitive: + id: 1101 + primitive_type: "" + primitives: + - id: 1100 + primitive_type: lane + - id: 1101 + primitive_type: lane + - id: 1102 + primitive_type: lane + - preferred_primitive: + id: 3501 + primitive_type: "" + primitives: + - id: 3500 + primitive_type: lane + - id: 3501 + primitive_type: lane + - id: 3502 + primitive_type: lane + uuid: + uuid: + - 6 + - 70 + - 102 + - 94 + - 252 + - 4 + - 42 + - 203 + - 16 + - 204 + - 158 + - 233 + - 14 + - 119 + - 47 + - 217 + allow_modification: false +operation_mode: + stamp: + sec: 37 + nanosec: 230399363 + mode: 2 + is_autoware_control_enabled: true + is_in_transition: false + is_stop_mode_available: true + is_autonomous_mode_available: true + is_local_mode_available: true + is_remote_mode_available: true +self_acceleration: + header: + stamp: + sec: 50 + nanosec: 365979114 + frame_id: /base_link + accel: + accel: + linear: + x: 0.528559 + y: -0.0304000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: 0.00000 + covariance: + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00100000 +self_odometry: + header: + stamp: + sec: 50 + nanosec: 365979114 + frame_id: map + child_frame_id: base_link + pose: + pose: + position: + x: 364.031 + y: 495.469 + z: 100.000 + orientation: + x: 0.00000 + y: 0.00000 + z: 0.707849 + w: 0.706364 + covariance: + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.000100000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + twist: + twist: + linear: + x: 10.4530 + y: 0.00000 + z: 0.00000 + angular: + x: 0.00000 + y: 0.00000 + z: -0.00290825 + covariance: + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 + - 0.00000 From b075d50e2abc3852a6b3075f2c2aef15e77a8351 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Mon, 25 Nov 2024 16:43:47 +0100 Subject: [PATCH 108/273] fix(autoware_pyplot): fix missing python3-dev dependency (#9461) Signed-off-by: Esteve Fernandez --- common/autoware_pyplot/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/common/autoware_pyplot/package.xml b/common/autoware_pyplot/package.xml index 1391db88cddff..af0237d0aead8 100644 --- a/common/autoware_pyplot/package.xml +++ b/common/autoware_pyplot/package.xml @@ -14,6 +14,7 @@ autoware_cmake pybind11-dev + python3-dev ament_cmake_ros ament_lint_auto From 81dab81cc764ce0a232f2cab643553faa8195527 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Tue, 26 Nov 2024 08:50:27 +0900 Subject: [PATCH 109/273] test(bpp_common): add unit test for object filtering (#9408) * add unit test for all function Signed-off-by: Go Sakayori * add function to create bounding nox object Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori --- .../test/test_objects_filtering.cpp | 301 ++++++++++++++++-- 1 file changed, 272 insertions(+), 29 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp index 88ed968d27b64..e7280c5bc150b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp @@ -14,12 +14,21 @@ #include "autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" +#include "autoware/behavior_path_planner_common/utils/utils.hpp" #include +#include #include +#include + #include #include +#include + +#include +#include +#include using PredictedObject = autoware_perception_msgs::msg::PredictedObject; using PredictedObjects = autoware_perception_msgs::msg::PredictedObjects; @@ -32,10 +41,34 @@ using tier4_planning_msgs::msg::PathPointWithLaneId; using autoware::test_utils::createPose; using autoware::test_utils::generateTrajectory; +using autoware::test_utils::make_lanelet; using autoware::universe_utils::createPoint; +using autoware::universe_utils::createVector3; constexpr double epsilon = 1e-6; +const auto intersection_map = + autoware::test_utils::make_map_bin_msg(autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_test_utils", "intersection/lanelet2_map.osm")); + +PredictedObject create_bounding_box_object( + const geometry_msgs::msg::Pose pose, + const geometry_msgs::msg::Vector3 velocity = geometry_msgs::msg::Vector3(), + const double x_dimension = 1.0, const double y_dimension = 1.0, + const std::vector & classification = std::vector()) +{ + PredictedObject object; + object.object_id = autoware::universe_utils::generateUUID(); + object.kinematics.initial_pose_with_covariance.pose = pose; + object.kinematics.initial_twist_with_covariance.twist.linear = velocity; + object.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + object.shape.dimensions.x = x_dimension; + object.shape.dimensions.y = y_dimension; + object.classification = classification; + + return object; +} + std::vector trajectory_to_path_with_lane_id(const Trajectory & trajectory) { std::vector path_with_lane_id; @@ -81,8 +114,7 @@ TEST(BehaviorPathPlanningObjectsFiltering, position_filter) using autoware::behavior_path_planner::utils::path_safety_checker::filter::position_filter; auto current_pos = createPoint(0.0, 0.0, 0.0); - PredictedObject object; - object.kinematics.initial_pose_with_covariance.pose = createPose(10.0, 0.0, 0.0, 0.0, 0.0, 0.0); + PredictedObject object = create_bounding_box_object(createPose(10.0, 0.0, 0.0, 0.0, 0.0, 0.0)); auto straight_trajectory = generateTrajectory(20, 1.0); double forward_distance = 20.0; double backward_distance = 1.0; @@ -129,23 +161,101 @@ TEST(BehaviorPathPlanningObjectsFiltering, is_within_circle) EXPECT_TRUE(is_within_circle(object_pos, ref_point, search_radius)); } +TEST(BehaviorPathPlanningObjectsFiltering, isCentroidWithinLanelet) +{ + using autoware::behavior_path_planner::utils::path_safety_checker::isCentroidWithinLanelet; + using autoware::behavior_path_planner::utils::path_safety_checker::isCentroidWithinLanelets; + + auto object = create_bounding_box_object(createPose(0.5, 0.0, 0.0, 0.0, 0.0, 0.0)); + auto lanelet = make_lanelet({0.0, 1.0}, {5.0, 1.0}, {0.0, -1.0}, {5.0, -1.0}); + double yaw_threshold = M_PI_2; + + EXPECT_TRUE(isCentroidWithinLanelet(object, lanelet, yaw_threshold)); + + object.kinematics.initial_pose_with_covariance.pose.position.x = 8.0; + EXPECT_FALSE(isCentroidWithinLanelet(object, lanelet, yaw_threshold)); + + lanelet::ConstLanelets target_lanelets; + target_lanelets.push_back(lanelet); + target_lanelets.push_back(make_lanelet({5.0, 1.0}, {10.0, 1.0}, {5.0, -1.0}, {10.0, -1.0})); + EXPECT_TRUE(isCentroidWithinLanelets(object, target_lanelets)); +} + +TEST(BehaviorPathPlanningObjectsFiltering, isPolygonOverlapLanelet) +{ + using autoware::behavior_path_planner::utils::toPolygon2d; + using autoware::behavior_path_planner::utils::path_safety_checker::isPolygonOverlapLanelet; + + PredictedObject object = create_bounding_box_object(createPose(0.5, 0.0, 0.0, 0.0, 0.0, 0.0)); + + auto lanelet = make_lanelet({0.0, 1.0}, {5.0, 1.0}, {0.0, -1.0}, {5.0, -1.0}); + double yaw_threshold = M_PI_2; + + EXPECT_TRUE(isPolygonOverlapLanelet(object, lanelet.polygon2d().basicPolygon())); + EXPECT_TRUE(isPolygonOverlapLanelet(object, toPolygon2d(lanelet))); + EXPECT_TRUE(isPolygonOverlapLanelet(object, lanelet, yaw_threshold)); + + object.kinematics.initial_pose_with_covariance.pose = createPose(10.0, 10.0, 0.0, 0.0, 0.0, 0.0); + EXPECT_FALSE(isPolygonOverlapLanelet(object, lanelet.polygon2d().basicPolygon())); + EXPECT_FALSE(isPolygonOverlapLanelet(object, toPolygon2d(lanelet))); + EXPECT_FALSE(isPolygonOverlapLanelet(object, lanelet, yaw_threshold)); +} + +TEST(BehaviorPathPlanningObjectsFiltering, filterObjects) +{ + using autoware::behavior_path_planner::utils::path_safety_checker::filterObjects; + using autoware::behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams; + using autoware::universe_utils::createVector3; + + std::shared_ptr objects = std::make_shared(); + std::shared_ptr route_handler = + std::make_shared(); + std::shared_ptr params = std::make_shared(); + params->ignore_object_velocity_threshold = false; + params->object_check_forward_distance = 20.0; + params->object_check_backward_distance = 10.0; + params->object_types_to_check.check_car = true; + route_handler->setMap(intersection_map); + lanelet::ConstLanelets current_lanes; + + current_lanes.push_back(route_handler->getLaneletsFromId(1000)); + current_lanes.push_back(route_handler->getLaneletsFromId(1010)); + auto current_pose = createPoint(360.22, 600.51, 0.0); + + EXPECT_TRUE( + filterObjects(objects, route_handler, current_lanes, current_pose, params).objects.empty()); + + ObjectClassification classification; + classification.label = ObjectClassification::Type::CAR; + classification.probability = 1.0; + + auto target_object = create_bounding_box_object( + createPose(360.22, 605.51, 0.0, 0.0, 0.0, 0.0), createVector3(1.0, 1.0, 0.0)); + target_object.classification.push_back(classification); + auto other_object = create_bounding_box_object( + createPose(370.22, 600.51, 0.0, 0.0, 0.0, 0.0), createVector3(1.0, 1.0, 0.0)); + other_object.classification.push_back(classification); + + objects->objects.push_back(target_object); + objects->objects.push_back(other_object); + + auto filtered_object = filterObjects(objects, route_handler, current_lanes, current_pose, params); + EXPECT_FALSE(filtered_object.objects.empty()); + EXPECT_EQ(filtered_object.objects.front().object_id, target_object.object_id); +} + TEST(BehaviorPathPlanningObjectsFiltering, filterObjectsByVelocity) { using autoware::behavior_path_planner::utils::path_safety_checker::filterObjectsByVelocity; PredictedObjects objects; - PredictedObject slow_obj; - PredictedObject fast_obj; + auto slow_obj = create_bounding_box_object( + createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), createVector3(2.0, 0.0, 0.0)); + auto fast_obj = create_bounding_box_object( + createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), createVector3(10.0, 0.0, 0.0)); double vel_thr = 5.0; - slow_obj.object_id = autoware::universe_utils::generateUUID(); - slow_obj.kinematics.initial_twist_with_covariance.twist.linear.x = 2.0; - slow_obj.kinematics.initial_twist_with_covariance.twist.linear.y = 0.0; objects.objects.push_back(slow_obj); - - fast_obj.object_id = autoware::universe_utils::generateUUID(); - fast_obj.kinematics.initial_twist_with_covariance.twist.linear.x = 10.0; - fast_obj.kinematics.initial_twist_with_covariance.twist.linear.y = 0.0; objects.objects.push_back(fast_obj); auto filtered_obj = filterObjectsByVelocity(objects, vel_thr, false); @@ -176,17 +286,12 @@ TEST(BehaviorPathPlanningObjectsFiltering, filterObjectsByPosition) double search_radius = 10.0; PredictedObjects objects; - PredictedObject far_obj; - PredictedObject near_obj; + auto far_obj = create_bounding_box_object(createPose(50.0, 0.0, 0.0, 0.0, 0.0, 0.0)); + auto near_obj = create_bounding_box_object(createPose(5.0, 0.0, 0.0, 0.0, 0.0, 0.0)); - near_obj.object_id = autoware::universe_utils::generateUUID(); - near_obj.kinematics.initial_pose_with_covariance.pose = createPose(5.0, 0.0, 0.0, 0.0, 0.0, 0.0); objects.objects.push_back(near_obj); - auto target_uuid = near_obj.object_id; - - far_obj.object_id = autoware::universe_utils::generateUUID(); - far_obj.kinematics.initial_pose_with_covariance.pose = createPose(50.0, 0.0, 0.0, 0.0, 0.0, 0.0); objects.objects.push_back(far_obj); + auto target_uuid = near_obj.object_id; filterObjectsByPosition(objects, straight_path, current_pos, forward_distance, backward_distance); @@ -202,6 +307,108 @@ TEST(BehaviorPathPlanningObjectsFiltering, filterObjectsByPosition) EXPECT_EQ(objects.objects.front().object_id, target_uuid); } +TEST(BehaviorPathPlanningObjectsFiltering, separateObjectsByLanelets) +{ + using autoware::behavior_path_planner::utils::path_safety_checker::isPolygonOverlapLanelet; + using autoware::behavior_path_planner::utils::path_safety_checker:: + separateObjectIndicesByLanelets; + using autoware::behavior_path_planner::utils::path_safety_checker::separateObjectsByLanelets; + + double yaw_threshold = M_PI_2; + + auto target_object = create_bounding_box_object(createPose(0.5, 0.0, 0.0, 0.0, 0.0, 0.0)); + auto other_object = create_bounding_box_object(createPose(-1.5, 0.0, 0.0, 0.0, 0.0, 0.0)); + + PredictedObjects objects; + objects.objects.push_back(target_object); + objects.objects.push_back(other_object); + + lanelet::ConstLanelets target_lanelets; + { + auto object_indices = separateObjectIndicesByLanelets( + objects, target_lanelets, + [](const auto & obj, const auto & lane, const auto & yaw_threshold) { + return isPolygonOverlapLanelet(obj, lane, yaw_threshold); + }, + yaw_threshold); + EXPECT_TRUE(object_indices.first.empty()); + EXPECT_TRUE(object_indices.second.empty()); + } + { + target_lanelets.push_back(make_lanelet({0.0, 1.0}, {5.0, 1.0}, {0.0, -1.0}, {5.0, -1.0})); + target_lanelets.push_back(make_lanelet({5.0, 1.0}, {10.0, 1.0}, {5.0, -1.0}, {10.0, -1.0})); + auto object_indices = separateObjectIndicesByLanelets( + objects, target_lanelets, + [](const auto & obj, const auto & lane, const auto & yaw_threshold) { + return isPolygonOverlapLanelet(obj, lane, yaw_threshold); + }, + yaw_threshold); + EXPECT_FALSE(object_indices.first.empty()); + EXPECT_FALSE(object_indices.second.empty()); + EXPECT_EQ(object_indices.first.front(), 0); + EXPECT_EQ(object_indices.second.front(), 1); + + auto filtered_object = separateObjectsByLanelets( + objects, target_lanelets, + [](const auto & obj, const auto & lane, const auto & yaw_threshold) { + return isPolygonOverlapLanelet(obj, lane, yaw_threshold); + }, + yaw_threshold); + EXPECT_FALSE(filtered_object.first.objects.empty()); + EXPECT_FALSE(filtered_object.second.objects.empty()); + EXPECT_EQ(filtered_object.first.objects.front().object_id, target_object.object_id); + EXPECT_EQ(filtered_object.second.objects.front().object_id, other_object.object_id); + } +} + +TEST(BehaviorPathPlanningObjectsFiltering, getPredictedPathFromObj) +{ + using autoware::behavior_path_planner::utils::path_safety_checker::getPredictedPathFromObj; + using autoware::behavior_path_planner::utils::path_safety_checker:: + PoseWithVelocityAndPolygonStamped; + using autoware::behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon; + + autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject object; + std::vector predicted_paths; + PredictedPathWithPolygon predicted_path; + + autoware_perception_msgs::msg::Shape shape; + shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; + shape.dimensions.x = 1.0; + shape.dimensions.y = 1.0; + + double velocity = 1.0; + + const auto path = [&](geometry_msgs::msg::Pose initial_pose) { + std::vector path; + geometry_msgs::msg::Pose pose; + for (size_t i = 0; i < 10; i++) { + auto time = static_cast(i); + pose.position.x = initial_pose.position.x + time * velocity; + pose.position.y = initial_pose.position.y; + PoseWithVelocityAndPolygonStamped obj_pose_with_poly( + time, pose, velocity, autoware::universe_utils::toPolygon2d(pose, shape)); + path.push_back(obj_pose_with_poly); + } + return path; + }; + + for (size_t i = 0; i < 2; i++) { + predicted_path.path = path(createPose(0.0, static_cast(i), 0.0, 0.0, 0.0, 0.0)); + predicted_path.confidence = 0.1f * (static_cast(i) + 1.0f); + predicted_paths.push_back(predicted_path); + } + object.predicted_paths = predicted_paths; + + bool use_all_predicted_path = true; + EXPECT_EQ(getPredictedPathFromObj(object, use_all_predicted_path).size(), 2); + + use_all_predicted_path = false; + auto extracted_path = getPredictedPathFromObj(object, use_all_predicted_path); + EXPECT_EQ(extracted_path.size(), 1); + EXPECT_DOUBLE_EQ(extracted_path.front().path.front().pose.position.y, 1.0); +} + TEST(BehaviorPathPlanningObjectsFiltering, createPredictedPath) { using autoware::behavior_path_planner::utils::path_safety_checker::createPredictedPath; @@ -257,22 +464,14 @@ TEST(BehaviorPathPlanningObjectsFiltering, transform) { using autoware::behavior_path_planner::utils::path_safety_checker::transform; auto velocity = autoware::universe_utils::createVector3(2.0, 0.0, 0.0); - auto angular = autoware::universe_utils::createVector3(0.0, 0.0, 0.0); - PredictedObject obj; - obj.object_id = autoware::universe_utils::generateUUID(); - obj.kinematics.initial_pose_with_covariance.pose = createPose(2.0, 0.0, 0.0, 0.0, 0.0, 0.0); - obj.kinematics.initial_twist_with_covariance.twist = - autoware::universe_utils::createTwist(velocity, angular); + auto obj = create_bounding_box_object( + createPose(2.0, 0.0, 0.0, 0.0, 0.0, 0.0), createVector3(2.0, 0.0, 0.0), 2.0, 1.0); autoware_perception_msgs::msg::PredictedPath predicted_path; auto straight_path = trajectory_to_predicted_path(generateTrajectory(5, 1.0)); straight_path.confidence = 0.6; straight_path.time_step.sec = 1.0; obj.kinematics.predicted_paths.push_back(straight_path); - obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; - obj.shape.dimensions.x = 2.0; - obj.shape.dimensions.y = 1.0; - obj.shape.dimensions.z = 1.0; double safety_check_time_horizon = 2.0; double safety_check_time_resolution = 0.5; @@ -356,6 +555,50 @@ TEST(BehaviorPathPlanningObjectsFiltering, filterObjectsByClass) EXPECT_TRUE(objects.objects.empty()); } +TEST(BehaviorPathPlanningObjectsFiltering, createTargetObjectsOnLane) +{ + using autoware::behavior_path_planner::utils::path_safety_checker::createTargetObjectsOnLane; + using autoware::behavior_path_planner::utils::path_safety_checker::ObjectsFilteringParams; + using autoware::universe_utils::createVector3; + + PredictedObjects objects; + std::shared_ptr route_handler = + std::make_shared(); + std::shared_ptr params = std::make_shared(); + params->object_lane_configuration = {true, true, true, true, true}; + params->include_opposite_lane = true; + params->invert_opposite_lane = false; + params->safety_check_time_horizon = 10.0; + params->safety_check_time_resolution = 1.0; + route_handler->setMap(intersection_map); + lanelet::ConstLanelets current_lanes; + + current_lanes.push_back(route_handler->getLaneletsFromId(1001)); + current_lanes.push_back(route_handler->getLaneletsFromId(1011)); + + ObjectClassification classification; + classification.label = ObjectClassification::Type::CAR; + classification.probability = 1.0; + + PredictedObject current_lane_object = + create_bounding_box_object(createPose(363.64, 565.03, 0.0, 0.0, 0.0, 0.0)); + PredictedObject right_lane_object = + create_bounding_box_object(createPose(366.91, 523.47, 0.0, 0.0, 0.0, 0.0)); + + objects.objects.push_back(current_lane_object); + objects.objects.push_back(right_lane_object); + + auto target_objects_on_lane = + createTargetObjectsOnLane(current_lanes, route_handler, objects, params); + EXPECT_FALSE(target_objects_on_lane.on_current_lane.empty()); + EXPECT_FALSE(target_objects_on_lane.on_right_lane.empty()); + EXPECT_TRUE(target_objects_on_lane.on_left_lane.empty()); + EXPECT_TRUE(target_objects_on_lane.on_other_lane.empty()); + + EXPECT_EQ(target_objects_on_lane.on_current_lane.front().uuid, current_lane_object.object_id); + EXPECT_EQ(target_objects_on_lane.on_right_lane.front().uuid, right_lane_object.object_id); +} + TEST(BehaviorPathPlanningObjectsFiltering, isTargetObjectType) { using autoware::behavior_path_planner::utils::path_safety_checker::isTargetObjectType; From e9093e6f09a3524f0b3a4756abdc88ec9637dbf9 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 26 Nov 2024 09:10:25 +0900 Subject: [PATCH 110/273] feat(autoware_ground_segmentation): grid data structure revision for efficiency improvement (#9297) * fix: replace point index to data index Signed-off-by: Taekjin LEE * feat: Use emplace_back instead of push_back for adding gnd_grids in node.cpp Signed-off-by: Taekjin LEE * fix: prep for non-sorted grid process Signed-off-by: Taekjin LEE * feat: Add Cell class and Grid class for grid-based segmentation Signed-off-by: Taekjin LEE * refactor: Add Cell and Grid classes for grid-based segmentation Signed-off-by: Taekjin LEE * feat: initialize new grid Signed-off-by: Taekjin LEE * refactor: Update Grid class initialization to use radians for azimuth size refactor: Update Grid class initialization to use radians for azimuth size refactor: Update Grid class initialization to use radians for azimuth size Signed-off-by: Taekjin LEE * refactor: Fix calculation of azimuth index in Grid class Signed-off-by: Taekjin LEE * feat: implement grid based segmentation, temporary logic Signed-off-by: Taekjin LEE * refactor: idx position convert methods Signed-off-by: Taekjin LEE * refactor: Update Grid class initialization to use radians for azimuth size Signed-off-by: Taekjin LEE * feat: reconnect grids filled Signed-off-by: Taekjin LEE * feat: grid initialization Signed-off-by: Taekjin LEE * refactor: Update Grid class initialization and reset methods, implement a segmentation logic refactor: Update Grid class initialization and reset methods, implement a segmentation logic refactor: replace original methods Signed-off-by: Taekjin LEE * feat: add time_keeper Signed-off-by: Taekjin LEE * refactor: add time keeper in grid class refactor: remove previous scan ground grid Signed-off-by: Taekjin LEE * refactor: optimize grid boundary calculations and use squared values for radius comparisons Signed-off-by: Taekjin LEE * fix: use pointer for prev cell Signed-off-by: Taekjin LEE * refactor: remove time keeper called too many times Signed-off-by: Taekjin LEE * fix: radial idx estimation fix Signed-off-by: Taekjin LEE * refactor: optimize ground bin average calculation fix: ground bin logic fix Signed-off-by: Taekjin LEE * refactor: make grid ground filter separate Signed-off-by: Taekjin LEE * refactor: remove unused code fix: azimuth grid index converter bug Signed-off-by: Taekjin LEE * fix: segmentation logic determination fix fix: cell connection bug fix Signed-off-by: Taekjin LEE * refactor: optimize pseudoArcTan2 function Signed-off-by: Taekjin LEE * refactor: update grid radial calculation Signed-off-by: Taekjin LEE * refactor: contain input cloud ptr Signed-off-by: Taekjin LEE * refactor: separate ground initialization Signed-off-by: Taekjin LEE * refactor: Remove unused code and optimize grid radial calculation Signed-off-by: Taekjin LEE * refactor: Inline functions for improved performance Signed-off-by: Taekjin LEE * feat: various azimuth interval per radial distance Signed-off-by: Taekjin LEE * refactor: Fix bug in grid ground filter segmentation logic and cell connection Remove unused code and optimize grid radial calculation Signed-off-by: Taekjin LEE * fix: add missing offset calculation Signed-off-by: Taekjin LEE * refactor: Improve grid ground filter segmentation logic and cell connection Optimize grid radial calculation and remove unused code Signed-off-by: Taekjin LEE * refactor: Remove debug print statements and optimize grid initialization Signed-off-by: Taekjin LEE * refactor: Update grid radial limit to 200.0m Signed-off-by: Taekjin LEE * refactor: Update grid size to 0.5m for improved ground segmentation Signed-off-by: Taekjin LEE * refactor: Improve grid ground filter segmentation logic Signed-off-by: Taekjin LEE * refactor: Optimize grid ground filter segmentation logic Signed-off-by: Taekjin LEE * refactor: Update logic order for fast segmentation Signed-off-by: Taekjin LEE * fix: resolve cppcheck issue Signed-off-by: Taekjin LEE * fix: pseudo atan2 fix for even distribution of azimuth Signed-off-by: Taekjin LEE * fix: remove unused next_grid_idx_ update Signed-off-by: Taekjin LEE * fix: introduce pseudo tangent to match result of pseudo arc tangent Signed-off-by: Taekjin LEE * style(pre-commit): autofix Signed-off-by: Taekjin LEE * fix: limit gradient Signed-off-by: Taekjin LEE * fix: bring previous average when the ground bin is empty Signed-off-by: Taekjin LEE * fix: back to constant azimuth interval grid Signed-off-by: Taekjin LEE * perf: remove division for efficiency Signed-off-by: Taekjin LEE * perf: remove division for efficiency Signed-off-by: Taekjin LEE * perf: contain radius and height to avoid double calculation Signed-off-by: Taekjin LEE * perf: optimize grid distance calculation for efficiency Signed-off-by: Taekjin LEE * style(pre-commit): autofix Signed-off-by: Taekjin LEE * perf: using isEmpty for efficiency Signed-off-by: Taekjin LEE * chore: initialization fix Signed-off-by: Taekjin LEE * perf: initial ground cell is integrated into the classify method for efficiency Signed-off-by: Taekjin LEE * perf: refactor grid initialization for efficiency Signed-off-by: Taekjin LEE * perf: optimize grid cell linking for efficiency Signed-off-by: Taekjin LEE * Revert "perf: initial ground cell is integrated into the classify method for efficiency" This reverts commit a4ab70b630f966d3e2827a07a0ec27079ecc78d2. Signed-off-by: Taekjin LEE * fix: fix pseudo atan2 bug Signed-off-by: Taekjin LEE * feat: various azimuth interval by range Signed-off-by: Taekjin LEE * perf: optimize pseudoArcTan2 function for efficiency Signed-off-by: Taekjin LEE * style(pre-commit): autofix Signed-off-by: Taekjin LEE * fix: avoid zero division on the slope estimation Signed-off-by: Taekjin LEE * fix: limit recursive search Signed-off-by: Taekjin LEE refactor: improve efficiency of recursiveSearch function Fix function parameter type in GridGroundFilter * refactor: add comments about unclassified case Signed-off-by: Taekjin LEE * chore: add comment to explain methods Signed-off-by: Taekjin LEE * refactor: remove unnecessary include statement Signed-off-by: Taekjin LEE * refactor: cast point_list size to int in getPointNum method Signed-off-by: Taekjin LEE * refactor: add index check in getCell method Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../CMakeLists.txt | 1 + .../config/scan_ground_filter.param.yaml | 2 +- .../src/scan_ground_filter/data.hpp | 69 +++ .../src/scan_ground_filter/grid.hpp | 501 ++++++++++++++++-- .../scan_ground_filter/grid_ground_filter.cpp | 492 +++++++++++++++++ .../scan_ground_filter/grid_ground_filter.hpp | 221 ++++++++ .../src/scan_ground_filter/node.cpp | 476 ++--------------- .../src/scan_ground_filter/node.hpp | 93 +--- 8 files changed, 1293 insertions(+), 562 deletions(-) create mode 100644 perception/autoware_ground_segmentation/src/scan_ground_filter/data.hpp create mode 100644 perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.cpp create mode 100644 perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.hpp diff --git a/perception/autoware_ground_segmentation/CMakeLists.txt b/perception/autoware_ground_segmentation/CMakeLists.txt index 9cf256b9492bb..957f06e8cecc3 100644 --- a/perception/autoware_ground_segmentation/CMakeLists.txt +++ b/perception/autoware_ground_segmentation/CMakeLists.txt @@ -25,6 +25,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/ray_ground_filter/node.cpp src/ransac_ground_filter/node.cpp src/scan_ground_filter/node.cpp + src/scan_ground_filter/grid_ground_filter.cpp ) target_link_libraries(${PROJECT_NAME} diff --git a/perception/autoware_ground_segmentation/config/scan_ground_filter.param.yaml b/perception/autoware_ground_segmentation/config/scan_ground_filter.param.yaml index 49c6c32624e75..ce07e83ecc833 100644 --- a/perception/autoware_ground_segmentation/config/scan_ground_filter.param.yaml +++ b/perception/autoware_ground_segmentation/config/scan_ground_filter.param.yaml @@ -6,7 +6,7 @@ use_virtual_ground_point: True split_height_distance: 0.2 non_ground_height_threshold: 0.20 - grid_size_m: 0.1 + grid_size_m: 0.5 grid_mode_switch_radius: 20.0 gnd_grid_buffer_size: 4 detection_range_z_max: 2.5 diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/data.hpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/data.hpp new file mode 100644 index 0000000000000..d2624ffb44c97 --- /dev/null +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/data.hpp @@ -0,0 +1,69 @@ +// 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 SCAN_GROUND_FILTER__DATA_HPP_ +#define SCAN_GROUND_FILTER__DATA_HPP_ + +#include + +#include + +namespace autoware::ground_segmentation +{ +using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr; + +class PclDataAccessor +{ +public: + PclDataAccessor() = default; + ~PclDataAccessor() = default; + + bool isInitialized() const { return data_offset_initialized_; } + + void setField(const PointCloud2ConstPtr & input) + { + data_offset_x_ = input->fields[pcl::getFieldIndex(*input, "x")].offset; + data_offset_y_ = input->fields[pcl::getFieldIndex(*input, "y")].offset; + data_offset_z_ = input->fields[pcl::getFieldIndex(*input, "z")].offset; + int intensity_index = pcl::getFieldIndex(*input, "intensity"); + if (intensity_index != -1) { + data_offset_intensity_ = input->fields[intensity_index].offset; + intensity_type_ = input->fields[intensity_index].datatype; + } else { + data_offset_intensity_ = -1; + } + data_offset_initialized_ = true; + } + + inline void getPoint( + const PointCloud2ConstPtr & input, const size_t data_index, pcl::PointXYZ & point) const + { + point.x = *reinterpret_cast(&input->data[data_index + data_offset_x_]); + point.y = *reinterpret_cast(&input->data[data_index + data_offset_y_]); + point.z = *reinterpret_cast(&input->data[data_index + data_offset_z_]); + } + +private: + // data field offsets + int data_offset_x_ = 0; + int data_offset_y_ = 0; + int data_offset_z_ = 0; + int data_offset_intensity_ = 0; + int intensity_type_ = 0; + bool data_offset_initialized_ = false; +}; + +} // namespace autoware::ground_segmentation + +#endif // SCAN_GROUND_FILTER__DATA_HPP_ diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/grid.hpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid.hpp index cd55d4a548211..05fcde9317abe 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/grid.hpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid.hpp @@ -17,93 +17,486 @@ #include #include +#include +#include #include +#include +#include +#include + +namespace +{ + +float pseudoArcTan2(const float y, const float x) +{ + // lightweight arc tangent + + // avoid divide-by-zero + if (y == 0.0f) { + if (x >= 0.0f) return 0.0f; + return M_PIf; + } + if (x == 0.0f) { + if (y >= 0.0f) return M_PI_2f; + return -M_PI_2f; + } + + const float x_abs = std::abs(x); + const float y_abs = std::abs(y); + + // divide to 8 zones + constexpr float M_2PIf = 2.0f * M_PIf; + constexpr float M_3PI_2f = 3.0f * M_PI_2f; + if (x_abs > y_abs) { + const float ratio = y_abs / x_abs; + const float angle = ratio * M_PI_4f; + if (y >= 0.0f) { + if (x >= 0.0f) return angle; // 1st zone + return M_PIf - angle; // 2nd zone + } else { + if (x >= 0.0f) return M_2PIf - angle; // 4th zone + return M_PIf + angle; // 3rd zone + } + } else { + const float ratio = x_abs / y_abs; + const float angle = ratio * M_PI_4f; + if (y >= 0.0f) { + if (x >= 0.0f) return M_PI_2f - angle; // 1st zone + return M_PI_2f + angle; // 2nd zone + } else { + if (x >= 0.0f) return M_3PI_2f + angle; // 4th zone + return M_3PI_2f - angle; // 3rd zone + } + } +} + +float pseudoTan(const float theta) +{ + // lightweight tangent + + // normalize the angle, range of [-pi/2, pi/2] + float normalized_theta = theta; + while (normalized_theta > M_PI_2f) { + normalized_theta -= M_PIf; + } + while (normalized_theta < -M_PI_2f) { + normalized_theta += M_PIf; + } + + // avoid divide-by-zero + if (normalized_theta == 0.0f) return 0.0f; + + if (std::abs(normalized_theta) <= 1.0f) { + return normalized_theta / M_PI_4f; + } + return std::copysign(M_PI_4f / (M_PI_2f - std::abs(normalized_theta)), normalized_theta); +} +} // namespace namespace autoware::ground_segmentation { +using autoware::universe_utils::ScopedTimeTrack; -class ScanGroundGrid +struct Point +{ + size_t index; + float distance; + float height; +}; + +// Concentric Zone Model (CZM) based polar grid +class Cell { public: - ScanGroundGrid() = default; - ~ScanGroundGrid() = default; + // list of point indices + std::vector point_list_; // point index and distance + + // method to check if the cell is empty + inline bool isEmpty() const { return point_list_.empty(); } + inline int getPointNum() const { return static_cast(point_list_.size()); } + + // index of the cell + int grid_idx_; + int radial_idx_; + int azimuth_idx_; + int next_grid_idx_; + int prev_grid_idx_; + + int scan_grid_root_idx_; + + // geometric properties of the cell + float center_radius_; + float center_azimuth_; + float radial_size_; + float azimuth_size_; + + // ground statistics of the points in the cell + float avg_height_; + float max_height_; + float min_height_; + float avg_radius_; + float gradient_; + float intercept_; + + // process flags + bool is_processed_ = false; + bool is_ground_initialized_ = false; + bool has_ground_ = false; +}; + +class Grid +{ +public: + Grid(const float origin_x, const float origin_y, const float origin_z) + : origin_x_(origin_x), origin_y_(origin_y), origin_z_(origin_z) + { + } + ~Grid() = default; + + void setTimeKeeper(std::shared_ptr time_keeper_ptr) + { + time_keeper_ = std::move(time_keeper_ptr); + } void initialize( - const float grid_size_m, const float grid_mode_switch_radius, const float virtual_lidar_z) + const float grid_dist_size, const float grid_azimuth_size, + const float grid_linearity_switch_radius) { - grid_size_m_ = grid_size_m; - mode_switch_radius_ = grid_mode_switch_radius; - virtual_lidar_z_ = virtual_lidar_z; - - // calculate parameters - inv_grid_size_m_ = 1.0f / grid_size_m_; - mode_switch_grid_id_ = mode_switch_radius_ * inv_grid_size_m_; - mode_switch_angle_rad_ = std::atan2(mode_switch_radius_, virtual_lidar_z_); - - grid_size_rad_ = universe_utils::normalizeRadian( - std::atan2(mode_switch_radius_ + grid_size_m_, virtual_lidar_z_)) - - universe_utils::normalizeRadian(mode_switch_angle_rad_); - inv_grid_size_rad_ = 1.0f / grid_size_rad_; - tan_grid_size_rad_ = std::tan(grid_size_rad_); - grid_id_offset_ = mode_switch_grid_id_ - mode_switch_angle_rad_ * inv_grid_size_rad_; + grid_dist_size_ = grid_dist_size; + grid_azimuth_size_ = grid_azimuth_size; + + // set grid linearity switch radius + grid_linearity_switch_num_ = static_cast(grid_linearity_switch_radius / grid_dist_size_); + grid_linearity_switch_radius_ = grid_linearity_switch_num_ * grid_dist_size_; + + // calculate grid parameters + grid_dist_size_rad_ = + pseudoArcTan2(grid_linearity_switch_radius_ + grid_dist_size_, origin_z_) - + pseudoArcTan2(grid_linearity_switch_radius_, origin_z_); + grid_dist_size_inv_ = 1.0f / grid_dist_size_; + + // generate grid geometry + setGridBoundaries(); + // initialize and resize cells + cells_.clear(); + cells_.resize(radial_idx_offsets_.back() + azimuth_grids_per_radial_.back()); + + // set cell geometry + setCellGeometry(); + + // set initialized flag is_initialized_ = true; } - float getGridSize(const float radius, const size_t grid_id) const + // method to add a point to the grid + void addPoint(const float x, const float y, const float z, const size_t point_idx) { - // check if initialized - if (!is_initialized_) { - throw std::runtime_error("ScanGroundGrid is not initialized."); + const float x_fixed = x - origin_x_; + const float y_fixed = y - origin_y_; + const float radius = std::sqrt(x_fixed * x_fixed + y_fixed * y_fixed); + const float azimuth = pseudoArcTan2(y_fixed, x_fixed); + + // calculate the grid id + const int grid_idx = getGridIdx(radius, azimuth); + + // check if the point is within the grid + if (grid_idx < 0) { + return; } + const size_t grid_idx_idx = static_cast(grid_idx); - float grid_size = grid_size_m_; - constexpr uint16_t back_steps_num = 1; + // add the point to the cell + cells_[grid_idx_idx].point_list_.emplace_back(Point{point_idx, radius, z}); + } + + size_t getGridSize() const { return cells_.size(); } - if (radius > mode_switch_radius_ && grid_id > mode_switch_grid_id_ + back_steps_num) { - // equivalent to grid_size = (std::tan(gamma) - std::tan(gamma - grid_size_rad_)) * - // virtual_lidar_z_ - // where gamma = normalizeRadian(std::atan2(radius, virtual_lidar_z_), 0.0f) - grid_size = radius - (radius - tan_grid_size_rad_ * virtual_lidar_z_) / - (1 + radius * tan_grid_size_rad_ / virtual_lidar_z_); + // method to get the cell + inline Cell & getCell(const int grid_idx) + { + const size_t idx = static_cast(grid_idx); + if (idx >= cells_.size()) { + throw std::out_of_range("Invalid grid index"); } - return grid_size; + return cells_[idx]; } - uint16_t getGridId(const float radius) const + void resetCells() { - // check if initialized - if (!is_initialized_) { - throw std::runtime_error("ScanGroundGrid is not initialized."); + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + for (auto & cell : cells_) { + cell.point_list_.clear(); + cell.is_processed_ = false; + cell.is_ground_initialized_ = false; + cell.has_ground_ = false; } + } - uint16_t grid_id = 0; - if (radius <= mode_switch_radius_) { - grid_id = static_cast(radius * inv_grid_size_m_); - } else { - auto gamma{universe_utils::normalizeRadian(std::atan2(radius, virtual_lidar_z_), 0.0f)}; - grid_id = grid_id_offset_ + gamma * inv_grid_size_rad_; + void setGridConnections() + { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + // iterate over grid cells + for (Cell & cell : cells_) { + // find and link the scan-grid root cell + cell.scan_grid_root_idx_ = cell.prev_grid_idx_; + while (cell.scan_grid_root_idx_ >= 0) { + const auto & prev_cell = cells_[cell.scan_grid_root_idx_]; + // if the previous cell has point, set the previous cell as the root cell + if (!prev_cell.isEmpty()) break; + // keep searching the previous cell + cell.scan_grid_root_idx_ = prev_cell.scan_grid_root_idx_; + } + // if the grid root idx reaches -1, finish the search } - return grid_id; } private: + // given parameters + float origin_x_; + float origin_y_; + float origin_z_; + float grid_dist_size_ = 1.0f; // meters + float grid_azimuth_size_ = 0.01f; // radians + float grid_linearity_switch_radius_ = 20.0f; // meters + + // calculated parameters + float grid_dist_size_rad_ = 0.0f; // radians + float grid_dist_size_inv_ = 0.0f; // inverse of the grid size in meters + int grid_linearity_switch_num_ = 0; // number of grids within the switch radius + float grid_linearity_switch_angle_ = 0.0f; // angle at the switch radius + float grid_size_rad_inv_ = 0.0f; // inverse of the grid size in radians bool is_initialized_ = false; // configured parameters - float grid_size_m_ = 0.0f; - float mode_switch_radius_ = 0.0f; - float virtual_lidar_z_ = 0.0f; + float grid_radial_limit_ = 200.0f; // meters - // calculated parameters - float inv_grid_size_m_ = 0.0f; - float grid_size_rad_ = 0.0f; - float inv_grid_size_rad_ = 0.0f; - float tan_grid_size_rad_ = 0.0f; - float mode_switch_grid_id_ = 0.0f; - float mode_switch_angle_rad_ = 0.0f; - float grid_id_offset_ = 0.0f; + // array of grid boundaries + std::vector grid_radial_boundaries_; + std::vector azimuth_grids_per_radial_; + std::vector azimuth_interval_per_radial_; + std::vector radial_idx_offsets_; + + // list of cells + std::vector cells_; + + // debug information + std::shared_ptr time_keeper_; + + // Generate grid geometry + // the grid is cylindrical mesh grid + // azimuth interval: constant angle + // radial interval: constant distance within mode switch radius + // constant elevation angle outside mode switch radius + void setGridBoundaries() + { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + // radial boundaries + { + // constant distance + for (int i = 0; i < grid_linearity_switch_num_; i++) { + grid_radial_boundaries_.push_back(i * grid_dist_size_); + } + // constant angle + grid_linearity_switch_angle_ = pseudoArcTan2(grid_linearity_switch_radius_, origin_z_); + float angle = grid_linearity_switch_angle_; + const float grid_angle_interval = + pseudoArcTan2(grid_linearity_switch_radius_ + grid_dist_size_, origin_z_) - angle; + grid_size_rad_inv_ = 1.0f / grid_angle_interval; + while (angle < M_PI_2) { + const float dist = pseudoTan(angle) * origin_z_; + grid_radial_boundaries_.push_back(dist); + if (dist > grid_radial_limit_) { + break; + } + angle += grid_angle_interval; + } + } + + const size_t radial_grid_num = grid_radial_boundaries_.size(); + + // azimuth boundaries + { + if (grid_azimuth_size_ <= 0) { + throw std::runtime_error("Grid azimuth size is not positive."); + } + + // number of azimuth grids per radial grid + azimuth_grids_per_radial_.resize(radial_grid_num); + azimuth_interval_per_radial_.resize(radial_grid_num); + azimuth_grids_per_radial_[0] = 1; + azimuth_interval_per_radial_[0] = 2.0f * M_PIf; + + const int max_azimuth_grid_num = static_cast(2.0 * M_PIf / grid_azimuth_size_); + + int divider = 1; + for (size_t i = radial_grid_num - 1; i > 0; --i) { + // set divider + const float radius = grid_radial_boundaries_[i]; + const int divider_next = std::ceil(grid_linearity_switch_radius_ / radius); + if (divider_next % divider == 0 && max_azimuth_grid_num % divider_next == 0) { + divider = divider_next; + } + // set azimuth grid number + const int grid_num = static_cast(max_azimuth_grid_num / divider); + const int azimuth_grid_num = std::max(std::min(grid_num, max_azimuth_grid_num), 1); + const float azimuth_interval_evened = 2.0f * M_PIf / azimuth_grid_num; + + azimuth_grids_per_radial_[i] = azimuth_grid_num; + azimuth_interval_per_radial_[i] = azimuth_interval_evened; + } + } + + // accumulate the number of azimuth grids per radial grid, set offset for each radial grid + radial_idx_offsets_.resize(radial_grid_num); + radial_idx_offsets_[0] = 0; + for (size_t i = 1; i < radial_grid_num; ++i) { + radial_idx_offsets_[i] = radial_idx_offsets_[i - 1] + azimuth_grids_per_radial_[i - 1]; + } + } + + int getAzimuthGridIdx(const int & radial_idx, const float & azimuth) const + { + const int azimuth_grid_num = azimuth_grids_per_radial_[radial_idx]; + + int azimuth_grid_idx = + static_cast(std::floor(azimuth / azimuth_interval_per_radial_[radial_idx])); + if (azimuth_grid_idx == azimuth_grid_num) { + // loop back to the first grid + azimuth_grid_idx = 0; + } + // constant azimuth interval + return azimuth_grid_idx; + } + + int getRadialIdx(const float & radius) const + { + // check if the point is within the grid + if (radius > grid_radial_limit_) { + return -1; + } + if (radius < 0) { + return -1; + } + + // determine the grid id + int grid_rad_idx = -1; + + // constant distance + if (radius < grid_linearity_switch_radius_) { + grid_rad_idx = static_cast(radius * grid_dist_size_inv_); + } else if (radius < grid_radial_limit_) { + const float angle = pseudoArcTan2(radius, origin_z_); + grid_rad_idx = grid_linearity_switch_num_ + + static_cast((angle - grid_linearity_switch_angle_) * grid_size_rad_inv_); + } + + return grid_rad_idx; + } + + int getGridIdx(const int & radial_idx, const int & azimuth_idx) const + { + return radial_idx_offsets_[radial_idx] + azimuth_idx; + } + + // method to determine the grid id of a point + // -1 means out of range + // range limit is horizon angle + int getGridIdx(const float & radius, const float & azimuth) const + { + const int grid_rad_idx = getRadialIdx(radius); + if (grid_rad_idx < 0) { + return -1; + } + + // azimuth grid id + const int grid_az_idx = getAzimuthGridIdx(grid_rad_idx, azimuth); + if (grid_az_idx < 0) { + return -1; + } + + return getGridIdx(grid_rad_idx, grid_az_idx); + } + + void getRadialAzimuthIdxFromCellIdx(const int cell_id, int & radial_idx, int & azimuth_idx) const + { + radial_idx = -1; + azimuth_idx = -1; + for (size_t i = 0; i < radial_idx_offsets_.size(); ++i) { + if (cell_id < radial_idx_offsets_[i]) { + radial_idx = i - 1; + azimuth_idx = cell_id - radial_idx_offsets_[i - 1]; + break; + } + } + if (cell_id >= radial_idx_offsets_.back()) { + radial_idx = radial_idx_offsets_.size() - 1; + azimuth_idx = cell_id - radial_idx_offsets_.back(); + } + } + + void setCellGeometry() + { + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + for (size_t idx = 0; idx < cells_.size(); ++idx) { + Cell & cell = cells_[idx]; + + int radial_idx = 0; + int azimuth_idx = 0; + getRadialAzimuthIdxFromCellIdx(idx, radial_idx, azimuth_idx); + + cell.grid_idx_ = idx; + cell.radial_idx_ = radial_idx; + cell.azimuth_idx_ = azimuth_idx; + + // set width of the cell + const auto radial_grid_num = static_cast(grid_radial_boundaries_.size() - 1); + if (radial_idx < radial_grid_num) { + cell.radial_size_ = + grid_radial_boundaries_[radial_idx + 1] - grid_radial_boundaries_[radial_idx]; + } else { + cell.radial_size_ = grid_radial_limit_ - grid_radial_boundaries_[radial_idx]; + } + cell.azimuth_size_ = azimuth_interval_per_radial_[radial_idx]; + + // set center of the cell + cell.center_radius_ = grid_radial_boundaries_[radial_idx] + cell.radial_size_ * 0.5f; + cell.center_azimuth_ = (static_cast(azimuth_idx) + 0.5f) * cell.azimuth_size_; + + // set next grid id, which is radially next + int next_grid_idx = -1; + // only if the next radial grid exists + if (radial_idx < radial_grid_num) { + // find nearest azimuth grid in the next radial grid + const float azimuth = cell.center_azimuth_; + const size_t azimuth_idx_next_radial_grid = getAzimuthGridIdx(radial_idx + 1, azimuth); + next_grid_idx = getGridIdx(radial_idx + 1, azimuth_idx_next_radial_grid); + } + cell.next_grid_idx_ = next_grid_idx; + + // set previous grid id, which is radially previous + int prev_grid_idx = -1; + // only if the previous radial grid exists + if (radial_idx > 0) { + // find nearest azimuth grid in the previous radial grid + const float azimuth = cell.center_azimuth_; + // constant azimuth interval + const size_t azimuth_idx_prev_radial_grid = getAzimuthGridIdx(radial_idx - 1, azimuth); + prev_grid_idx = getGridIdx(radial_idx - 1, azimuth_idx_prev_radial_grid); + } + cell.prev_grid_idx_ = prev_grid_idx; + cell.scan_grid_root_idx_ = -1; + } + } }; } // namespace autoware::ground_segmentation diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.cpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.cpp new file mode 100644 index 0000000000000..8b754357cd45f --- /dev/null +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.cpp @@ -0,0 +1,492 @@ +// 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 "grid_ground_filter.hpp" + +#include "data.hpp" + +#include + +namespace autoware::ground_segmentation +{ + +// assign the pointcloud data to the grid +void GridGroundFilter::convert() +{ + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + const size_t in_cloud_data_size = in_cloud_->data.size(); + const size_t in_cloud_point_step = in_cloud_->point_step; + + for (size_t data_index = 0; data_index + in_cloud_point_step <= in_cloud_data_size; + data_index += in_cloud_point_step) { + // Get Point + pcl::PointXYZ input_point; + data_accessor_.getPoint(in_cloud_, data_index, input_point); + grid_ptr_->addPoint(input_point.x, input_point.y, input_point.z, data_index); + } +} + +// preprocess the grid data, set the grid connections +void GridGroundFilter::preprocess() +{ + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + // eliminate empty cells from connection for efficiency + grid_ptr_->setGridConnections(); +} + +// recursive search for the ground grid cell close to the grid origin +bool GridGroundFilter::recursiveSearch( + const int check_idx, const int search_cnt, std::vector & idx) const +{ + // set the maximum search count + constexpr size_t count_limit = 1023; + return recursiveSearch(check_idx, search_cnt, idx, count_limit); +} + +bool GridGroundFilter::recursiveSearch( + const int check_idx, const int search_cnt, std::vector & idx, size_t count) const +{ + if (count == 0) { + return false; + } + count -= 1; + // recursive search + if (check_idx < 0) { + return false; + } + if (search_cnt == 0) { + return true; + } + const auto & check_cell = grid_ptr_->getCell(check_idx); + if (check_cell.has_ground_) { + // the cell has ground, add the index to the list, and search previous cell + idx.push_back(check_idx); + return recursiveSearch(check_cell.scan_grid_root_idx_, search_cnt - 1, idx, count); + } + // if the cell does not have ground, search previous cell + return recursiveSearch(check_cell.scan_grid_root_idx_, search_cnt, idx, count); +} + +// fit the line from the ground grid cells +void GridGroundFilter::fitLineFromGndGrid(const std::vector & idx, float & a, float & b) const +{ + // if the idx is empty, the line is not defined + if (idx.empty()) { + a = 0.0f; + b = 0.0f; + return; + } + // if the idx is length of 1, the line is zero-crossing line + if (idx.size() == 1) { + const auto & cell = grid_ptr_->getCell(idx.front()); + a = cell.avg_height_ / cell.avg_radius_; + b = 0.0f; + return; + } + // calculate the line by least square method + float sum_x = 0.0f; + float sum_y = 0.0f; + float sum_xy = 0.0f; + float sum_x2 = 0.0f; + for (const auto & i : idx) { + const auto & cell = grid_ptr_->getCell(i); + sum_x += cell.avg_radius_; + sum_y += cell.avg_height_; + sum_xy += cell.avg_radius_ * cell.avg_height_; + sum_x2 += cell.avg_radius_ * cell.avg_radius_; + } + const float n = static_cast(idx.size()); + const float denominator = n * sum_x2 - sum_x * sum_x; + if (denominator != 0.0f) { + a = (n * sum_xy - sum_x * sum_y) / denominator; + a = std::clamp(a, -param_.global_slope_max_ratio, param_.global_slope_max_ratio); + b = (sum_y - a * sum_x) / n; + } else { + const auto & cell = grid_ptr_->getCell(idx.front()); + a = cell.avg_height_ / cell.avg_radius_; + b = 0.0f; + } +} + +// process the grid data to initialize the ground cells prior to the ground segmentation +void GridGroundFilter::initializeGround(pcl::PointIndices & out_no_ground_indices) +{ + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + const auto grid_size = grid_ptr_->getGridSize(); + // loop over grid cells + for (size_t idx = 0; idx < grid_size; idx++) { + auto & cell = grid_ptr_->getCell(idx); + if (cell.is_ground_initialized_) continue; + // if the cell is empty, skip + if (cell.isEmpty()) continue; + + // check scan root grid + if (cell.scan_grid_root_idx_ >= 0) { + const Cell & prev_cell = grid_ptr_->getCell(cell.scan_grid_root_idx_); + if (prev_cell.is_ground_initialized_) { + cell.is_ground_initialized_ = true; + continue; + } + } + + // initialize ground in this cell + bool is_ground_found = false; + PointsCentroid ground_bin; + + for (const auto & pt : cell.point_list_) { + const size_t & pt_idx = pt.index; + const float & radius = pt.distance; + const float & height = pt.height; + + const float global_slope_threshold = param_.global_slope_max_ratio * radius; + if (height >= global_slope_threshold && height > param_.non_ground_height_threshold) { + // this point is obstacle + out_no_ground_indices.indices.push_back(pt_idx); + } else if ( + abs(height) < global_slope_threshold && abs(height) < param_.non_ground_height_threshold) { + // this point is ground + ground_bin.addPoint(radius, height, pt_idx); + is_ground_found = true; + } + // else, this point is not classified, not ground nor obstacle + } + cell.is_processed_ = true; + cell.has_ground_ = is_ground_found; + if (is_ground_found) { + cell.is_ground_initialized_ = true; + ground_bin.processAverage(); + cell.avg_height_ = ground_bin.getAverageHeight(); + cell.avg_radius_ = ground_bin.getAverageRadius(); + cell.max_height_ = ground_bin.getMaxHeight(); + cell.min_height_ = ground_bin.getMinHeight(); + cell.gradient_ = std::clamp( + cell.avg_height_ / cell.avg_radius_, -param_.global_slope_max_ratio, + param_.global_slope_max_ratio); + cell.intercept_ = 0.0f; + } else { + cell.is_ground_initialized_ = false; + } + } +} + +// segment the point in the cell, logic for the continuous cell +void GridGroundFilter::SegmentContinuousCell( + const Cell & cell, PointsCentroid & ground_bin, pcl::PointIndices & out_no_ground_indices) +{ + const Cell & prev_cell = grid_ptr_->getCell(cell.scan_grid_root_idx_); + const float local_thresh_angle_ratio = std::tan(DEG2RAD(5.0)); + + // loop over points in the cell + for (const auto & pt : cell.point_list_) { + const size_t & pt_idx = pt.index; + const float & radius = pt.distance; + const float & height = pt.height; + + // 1. height is out-of-range + const float delta_z = height - prev_cell.avg_height_; + if (delta_z > param_.detection_range_z_max) { + // this point is out-of-range + continue; + } + + // 2. the angle is exceed the global slope threshold + if (height > param_.global_slope_max_ratio * radius) { + // this point is obstacle + out_no_ground_indices.indices.push_back(pt_idx); + // go to the next point + continue; + } + + // 3. local slope + const float delta_radius = radius - prev_cell.avg_radius_; + if (abs(delta_z) < param_.global_slope_max_ratio * delta_radius) { + // this point is ground + ground_bin.addPoint(radius, height, pt_idx); + // go to the next point + continue; + } + + // 3. height from the estimated ground + const float next_gnd_z = cell.gradient_ * radius + cell.intercept_; + const float gnd_z_local_thresh = local_thresh_angle_ratio * delta_radius; + const float delta_gnd_z = height - next_gnd_z; + const float gnd_z_threshold = param_.non_ground_height_threshold + gnd_z_local_thresh; + if (delta_gnd_z > gnd_z_threshold) { + // this point is obstacle + out_no_ground_indices.indices.push_back(pt_idx); + // go to the next point + continue; + } + if (abs(delta_gnd_z) <= gnd_z_threshold) { + // this point is ground + ground_bin.addPoint(radius, height, pt_idx); + // go to the next point + continue; + } + // else, this point is not classified, not ground nor obstacle + } +} + +// segment the point in the cell, logic for the discontinuous cell +void GridGroundFilter::SegmentDiscontinuousCell( + const Cell & cell, PointsCentroid & ground_bin, pcl::PointIndices & out_no_ground_indices) +{ + const Cell & prev_cell = grid_ptr_->getCell(cell.scan_grid_root_idx_); + + // loop over points in the cell + for (const auto & pt : cell.point_list_) { + const size_t & pt_idx = pt.index; + const float & radius = pt.distance; + const float & height = pt.height; + + // 1. height is out-of-range + const float delta_avg_z = height - prev_cell.avg_height_; + if (delta_avg_z > param_.detection_range_z_max) { + // this point is out-of-range + continue; + } + + // 2. the angle is exceed the global slope threshold + if (height > param_.global_slope_max_ratio * radius) { + // this point is obstacle + out_no_ground_indices.indices.push_back(pt_idx); + // go to the next point + continue; + } + // 3. local slope + const float delta_radius = radius - prev_cell.avg_radius_; + const float global_slope_threshold = param_.global_slope_max_ratio * delta_radius; + if (abs(delta_avg_z) < global_slope_threshold) { + // this point is ground + ground_bin.addPoint(radius, height, pt_idx); + // go to the next point + continue; + } + // 4. height from the estimated ground + if (abs(delta_avg_z) < param_.non_ground_height_threshold) { + // this point is ground + ground_bin.addPoint(radius, height, pt_idx); + // go to the next point + continue; + } + const float delta_max_z = height - prev_cell.max_height_; + if (abs(delta_max_z) < param_.non_ground_height_threshold) { + // this point is ground + ground_bin.addPoint(radius, height, pt_idx); + // go to the next point + continue; + } + // 5. obstacle from local slope + if (delta_avg_z >= global_slope_threshold) { + // this point is obstacle + out_no_ground_indices.indices.push_back(pt_idx); + // go to the next point + continue; + } + // else, this point is not classified, not ground nor obstacle + } +} + +// segment the point in the cell, logic for the break cell +void GridGroundFilter::SegmentBreakCell( + const Cell & cell, PointsCentroid & ground_bin, pcl::PointIndices & out_no_ground_indices) +{ + const Cell & prev_cell = grid_ptr_->getCell(cell.scan_grid_root_idx_); + + // loop over points in the cell + for (const auto & pt : cell.point_list_) { + const size_t & pt_idx = pt.index; + const float & radius = pt.distance; + const float & height = pt.height; + + // 1. height is out-of-range + const float delta_z = height - prev_cell.avg_height_; + if (delta_z > param_.detection_range_z_max) { + // this point is out-of-range + continue; + } + + // 2. the angle is exceed the global slope threshold + if (height > param_.global_slope_max_ratio * radius) { + // this point is obstacle + out_no_ground_indices.indices.push_back(pt_idx); + // go to the next point + continue; + } + + // 3. the point is over discontinuous grid + const float delta_radius = radius - prev_cell.avg_radius_; + const float global_slope_threshold = param_.global_slope_max_ratio * delta_radius; + if (abs(delta_z) < global_slope_threshold) { + // this point is ground + ground_bin.addPoint(radius, height, pt_idx); + // go to the next point + continue; + } + if (delta_z >= global_slope_threshold) { + // this point is obstacle + out_no_ground_indices.indices.push_back(pt_idx); + // go to the next point + continue; + } + // else, this point is not classified, not ground nor obstacle + } +} + +// classify the point cloud into ground and non-ground points +void GridGroundFilter::classify(pcl::PointIndices & out_no_ground_indices) +{ + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + // loop over grid cells + const auto grid_size = grid_ptr_->getGridSize(); + for (size_t idx = 0; idx < grid_size; idx++) { + auto & cell = grid_ptr_->getCell(idx); + // if the cell is empty, skip + if (cell.isEmpty()) continue; + if (cell.is_processed_) continue; + + // set a cell pointer for the previous cell + // check scan root grid + if (cell.scan_grid_root_idx_ < 0) continue; + const Cell & prev_cell = grid_ptr_->getCell(cell.scan_grid_root_idx_); + if (!(prev_cell.is_ground_initialized_)) continue; + + // get current cell gradient and intercept + std::vector grid_idcs; + { + const int search_count = param_.gnd_grid_buffer_size; + const int check_cell_idx = cell.scan_grid_root_idx_; + recursiveSearch(check_cell_idx, search_count, grid_idcs); + } + + // segment the ground and non-ground points + enum SegmentationMode { NONE, CONTINUOUS, DISCONTINUOUS, BREAK }; + SegmentationMode mode = SegmentationMode::NONE; + { + const int front_radial_id = + grid_ptr_->getCell(grid_idcs.back()).radial_idx_ + grid_idcs.size(); + const float radial_diff_between_cells = cell.center_radius_ - prev_cell.center_radius_; + + if (radial_diff_between_cells < param_.gnd_grid_continual_thresh * cell.radial_size_) { + if (cell.radial_idx_ - front_radial_id < param_.gnd_grid_continual_thresh) { + mode = SegmentationMode::CONTINUOUS; + } else { + mode = SegmentationMode::DISCONTINUOUS; + } + } else { + mode = SegmentationMode::BREAK; + } + } + + { + PointsCentroid ground_bin; + if (mode == SegmentationMode::CONTINUOUS) { + // calculate the gradient and intercept by least square method + float a, b; + fitLineFromGndGrid(grid_idcs, a, b); + cell.gradient_ = a; + cell.intercept_ = b; + + SegmentContinuousCell(cell, ground_bin, out_no_ground_indices); + } else if (mode == SegmentationMode::DISCONTINUOUS) { + SegmentDiscontinuousCell(cell, ground_bin, out_no_ground_indices); + } else if (mode == SegmentationMode::BREAK) { + SegmentBreakCell(cell, ground_bin, out_no_ground_indices); + } + + // recheck ground bin + if ( + param_.use_recheck_ground_cluster && cell.avg_radius_ > param_.grid_mode_switch_radius && + ground_bin.getGroundPointNum() > 0) { + // recheck the ground cluster + float reference_height = 0; + if (param_.use_lowest_point) { + reference_height = ground_bin.getMinHeightOnly(); + } else { + ground_bin.processAverage(); + reference_height = ground_bin.getAverageHeight(); + } + const float threshold = reference_height + param_.non_ground_height_threshold; + const std::vector & gnd_indices = ground_bin.getIndicesRef(); + const std::vector & height_list = ground_bin.getHeightListRef(); + for (size_t j = 0; j < height_list.size(); ++j) { + if (height_list.at(j) >= threshold) { + // fill the non-ground indices + out_no_ground_indices.indices.push_back(gnd_indices.at(j)); + // mark the point as non-ground + ground_bin.is_ground_list.at(j) = false; + } + } + } + + // finalize current cell, update the cell ground information + if (ground_bin.getGroundPointNum() > 0) { + ground_bin.processAverage(); + cell.avg_height_ = ground_bin.getAverageHeight(); + cell.avg_radius_ = ground_bin.getAverageRadius(); + cell.max_height_ = ground_bin.getMaxHeight(); + cell.min_height_ = ground_bin.getMinHeight(); + cell.has_ground_ = true; + } else { + // copy previous cell + cell.avg_radius_ = prev_cell.avg_radius_; + cell.avg_height_ = prev_cell.avg_height_; + cell.max_height_ = prev_cell.max_height_; + cell.min_height_ = prev_cell.min_height_; + cell.has_ground_ = false; + } + + cell.is_processed_ = true; + } + } +} + +// process the point cloud to segment the ground points +void GridGroundFilter::process( + const PointCloud2ConstPtr & in_cloud, pcl::PointIndices & out_no_ground_indices) +{ + std::unique_ptr st_ptr; + if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); + + // set input cloud + in_cloud_ = in_cloud; + + // clear the output indices + out_no_ground_indices.indices.clear(); + + // reset grid cells + grid_ptr_->resetCells(); + + // 1. assign points to grid cells + convert(); + + // 2. cell preprocess + preprocess(); + + // 3. initialize ground + initializeGround(out_no_ground_indices); + + // 4. classify point cloud + classify(out_no_ground_indices); +} + +} // namespace autoware::ground_segmentation diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.hpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.hpp new file mode 100644 index 0000000000000..0024582f22b0a --- /dev/null +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.hpp @@ -0,0 +1,221 @@ +// 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 SCAN_GROUND_FILTER__GRID_GROUND_FILTER_HPP_ +#define SCAN_GROUND_FILTER__GRID_GROUND_FILTER_HPP_ + +#include "data.hpp" +#include "grid.hpp" + +#include +#include + +#include + +#include + +#include +#include +#include +#include +#include + +namespace autoware::ground_segmentation +{ +using PointCloud2ConstPtr = sensor_msgs::msg::PointCloud2::ConstSharedPtr; + +struct PointsCentroid +{ + float radius_avg; + float height_avg; + float height_max; + float height_min; + uint16_t grid_id; + std::vector pcl_indices; + std::vector height_list; + std::vector radius_list; + std::vector is_ground_list; + + PointsCentroid() + : radius_avg(0.0f), height_avg(0.0f), height_max(-10.0f), height_min(10.0f), grid_id(0) + { + } + + void initialize() + { + radius_avg = 0.0f; + height_avg = 0.0f; + height_max = -10.0f; + height_min = 10.0f; + grid_id = 0; + pcl_indices.clear(); + height_list.clear(); + radius_list.clear(); + is_ground_list.clear(); + } + + inline void addPoint(const float radius, const float height, const size_t index) + { + pcl_indices.push_back(index); + height_list.push_back(height); + radius_list.push_back(radius); + is_ground_list.push_back(true); + } + + int getGroundPointNum() const + { + return std::count(is_ground_list.begin(), is_ground_list.end(), true); + } + + void processAverage() + { + // process only if is_ground_list is true + const int ground_point_num = getGroundPointNum(); + if (ground_point_num == 0) { + return; + } + + float radius_sum = 0.0f; + float height_sum = 0.0f; + height_max = -10.0f; + height_min = 10.0f; + + for (size_t i = 0; i < is_ground_list.size(); ++i) { + if (!is_ground_list[i]) { + continue; + } + radius_sum += radius_list[i]; + height_sum += height_list[i]; + height_max = std::max(height_max, height_list[i]); + height_min = std::min(height_min, height_list[i]); + } + + radius_avg = radius_sum / ground_point_num; + height_avg = height_sum / ground_point_num; + } + + float getMinHeightOnly() const + { + float min_height = 10.0f; + for (size_t i = 0; i < is_ground_list.size(); ++i) { + if (!is_ground_list[i]) { + continue; + } + min_height = std::min(min_height, height_list[i]); + } + return min_height; + } + + float getAverageSlope() const { return std::atan2(height_avg, radius_avg); } + float getAverageHeight() const { return height_avg; } + float getAverageRadius() const { return radius_avg; } + float getMaxHeight() const { return height_max; } + float getMinHeight() const { return height_min; } + const std::vector & getIndicesRef() const { return pcl_indices; } + const std::vector & getHeightListRef() const { return height_list; } +}; + +struct GridGroundFilterParameter +{ + // parameters + float global_slope_max_angle_rad; + float local_slope_max_angle_rad; + float global_slope_max_ratio; + float local_slope_max_ratio; + float radial_divider_angle_rad; + size_t radial_dividers_num; + + bool use_recheck_ground_cluster; + bool use_lowest_point; + float detection_range_z_max; + float non_ground_height_threshold; + const uint16_t gnd_grid_continual_thresh = 3; + + float grid_size_m; + float grid_mode_switch_radius; + int gnd_grid_buffer_size; + float virtual_lidar_x; + float virtual_lidar_y; + float virtual_lidar_z; +}; + +class GridGroundFilter +{ +public: + explicit GridGroundFilter(GridGroundFilterParameter & param) : param_(param) + { + // calculate derived parameters + param_.global_slope_max_ratio = std::tan(param_.global_slope_max_angle_rad); + param_.local_slope_max_ratio = std::tan(param_.local_slope_max_angle_rad); + param_.radial_dividers_num = std::ceil(2.0 * M_PI / param_.radial_divider_angle_rad); + + // initialize grid pointer + grid_ptr_ = std::make_unique( + param_.virtual_lidar_x, param_.virtual_lidar_y, param_.virtual_lidar_z); + grid_ptr_->initialize( + param_.grid_size_m, param_.radial_divider_angle_rad, param_.grid_mode_switch_radius); + } + ~GridGroundFilter() = default; + + void setTimeKeeper(std::shared_ptr time_keeper_ptr) + { + time_keeper_ = std::move(time_keeper_ptr); + + // set time keeper for grid + grid_ptr_->setTimeKeeper(time_keeper_); + } + + void setDataAccessor(const PointCloud2ConstPtr & in_cloud) + { + if (!data_accessor_.isInitialized()) { + data_accessor_.setField(in_cloud); + } + } + void process(const PointCloud2ConstPtr & in_cloud, pcl::PointIndices & out_no_ground_indices); + +private: + // parameters + GridGroundFilterParameter param_; + + // data + PointCloud2ConstPtr in_cloud_; + PclDataAccessor data_accessor_; + + // grid data + std::unique_ptr grid_ptr_; + + // debug information + std::shared_ptr time_keeper_; + + bool recursiveSearch(const int check_idx, const int search_cnt, std::vector & idx) const; + bool recursiveSearch( + const int check_idx, const int search_cnt, std::vector & idx, size_t count) const; + void fitLineFromGndGrid(const std::vector & idx, float & a, float & b) const; + + void convert(); + void preprocess(); + void initializeGround(pcl::PointIndices & out_no_ground_indices); + + void SegmentContinuousCell( + const Cell & cell, PointsCentroid & ground_bin, pcl::PointIndices & out_no_ground_indices); + void SegmentDiscontinuousCell( + const Cell & cell, PointsCentroid & ground_bin, pcl::PointIndices & out_no_ground_indices); + void SegmentBreakCell( + const Cell & cell, PointsCentroid & ground_bin, pcl::PointIndices & out_no_ground_indices); + void classify(pcl::PointIndices & out_no_ground_indices); +}; + +} // namespace autoware::ground_segmentation + +#endif // SCAN_GROUND_FILTER__GRID_GROUND_FILTER_HPP_ 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 0d7c41802cca9..488de2da47f91 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.cpp @@ -14,6 +14,8 @@ #include "node.hpp" +#include "grid_ground_filter.hpp" + #include #include #include @@ -55,8 +57,6 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & local_slope_max_ratio_ = std::tan(local_slope_max_angle_rad_); split_points_distance_tolerance_ = static_cast(declare_parameter("split_points_distance_tolerance")); - split_points_distance_tolerance_square_ = - split_points_distance_tolerance_ * split_points_distance_tolerance_; // vehicle info vehicle_info_ = VehicleInfoUtils(*this).getVehicleInfo(); @@ -81,11 +81,27 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & gnd_grid_buffer_size_ = declare_parameter("gnd_grid_buffer_size"); virtual_lidar_z_ = vehicle_info_.vehicle_height_m; - // initialize grid - grid_.initialize(grid_size_m_, grid_mode_switch_radius_, virtual_lidar_z_); - - // data access - data_offset_initialized_ = false; + // initialize grid filter + { + GridGroundFilterParameter param; + param.global_slope_max_angle_rad = global_slope_max_angle_rad_; + param.local_slope_max_angle_rad = local_slope_max_angle_rad_; + param.radial_divider_angle_rad = radial_divider_angle_rad_; + + param.use_recheck_ground_cluster = use_recheck_ground_cluster_; + param.use_lowest_point = use_lowest_point_; + param.detection_range_z_max = detection_range_z_max_; + param.non_ground_height_threshold = non_ground_height_threshold_; + + param.grid_size_m = grid_size_m_; + param.grid_mode_switch_radius = grid_mode_switch_radius_; + param.gnd_grid_buffer_size = gnd_grid_buffer_size_; + param.virtual_lidar_x = vehicle_info_.wheel_base_m / 2.0f + center_pcl_shift_; + param.virtual_lidar_y = 0.0f; + param.virtual_lidar_z = virtual_lidar_z_; + + grid_ground_filter_ptr_ = std::make_unique(param); + } } using std::placeholders::_1; @@ -108,86 +124,9 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions & "~/debug/processing_time_detail_ms", 1); auto time_keeper = autoware::universe_utils::TimeKeeper(detailed_processing_time_publisher_); time_keeper_ = std::make_shared(time_keeper); - } - } -} -inline void ScanGroundFilterComponent::set_field_index_offsets(const PointCloud2ConstPtr & input) -{ - data_offset_x_ = input->fields[pcl::getFieldIndex(*input, "x")].offset; - data_offset_y_ = input->fields[pcl::getFieldIndex(*input, "y")].offset; - data_offset_z_ = input->fields[pcl::getFieldIndex(*input, "z")].offset; - int intensity_index = pcl::getFieldIndex(*input, "intensity"); - if (intensity_index != -1) { - data_offset_intensity_ = input->fields[intensity_index].offset; - intensity_type_ = input->fields[intensity_index].datatype; - } else { - data_offset_intensity_ = -1; - } - data_offset_initialized_ = true; -} - -inline void ScanGroundFilterComponent::get_point_from_data_index( - const PointCloud2ConstPtr & input, const size_t data_index, pcl::PointXYZ & point) const -{ - point.x = *reinterpret_cast(&input->data[data_index + data_offset_x_]); - point.y = *reinterpret_cast(&input->data[data_index + data_offset_y_]); - point.z = *reinterpret_cast(&input->data[data_index + data_offset_z_]); -} - -void ScanGroundFilterComponent::convertPointcloudGridScan( - const PointCloud2ConstPtr & in_cloud, - std::vector & out_radial_ordered_points) const -{ - std::unique_ptr st_ptr; - if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - - out_radial_ordered_points.resize(radial_dividers_num_); - PointData current_point; - - const auto inv_radial_divider_angle_rad = 1.0f / radial_divider_angle_rad_; - const auto x_shift = vehicle_info_.wheel_base_m / 2.0f + center_pcl_shift_; - - const size_t in_cloud_data_size = in_cloud->data.size(); - const size_t in_cloud_point_step = in_cloud->point_step; - - { // grouping pointcloud by its azimuth angle - std::unique_ptr inner_st_ptr; - if (time_keeper_) - inner_st_ptr = std::make_unique("azimuth_angle_grouping", *time_keeper_); - - size_t point_index = 0; - pcl::PointXYZ input_point; - for (size_t data_index = 0; data_index + in_cloud_point_step <= in_cloud_data_size; - data_index += in_cloud_point_step) { - // Get Point - get_point_from_data_index(in_cloud, data_index, input_point); - - // determine the azimuth angle group - auto x{input_point.x - x_shift}; // base on front wheel center - auto radius{static_cast(std::hypot(x, input_point.y))}; - auto theta{normalizeRadian(std::atan2(x, input_point.y), 0.0)}; - auto radial_div{static_cast(std::floor(theta * inv_radial_divider_angle_rad))}; - - current_point.radius = radius; - current_point.point_state = PointLabel::INIT; - current_point.orig_index = point_index; - current_point.grid_id = grid_.getGridId(radius); - - // store the point in the corresponding radial division - out_radial_ordered_points[radial_div].emplace_back(current_point); - ++point_index; - } - } - - { // sorting pointcloud by distance, on each azimuth angle group - std::unique_ptr inner_st_ptr; - if (time_keeper_) inner_st_ptr = std::make_unique("sort", *time_keeper_); - - for (size_t i = 0; i < radial_dividers_num_; ++i) { - std::sort( - out_radial_ordered_points[i].begin(), out_radial_ordered_points[i].end(), - [](const PointData & a, const PointData & b) { return a.radius < b.radius; }); + // set time keeper to grid + grid_ground_filter_ptr_->setTimeKeeper(time_keeper_); } } } @@ -212,12 +151,11 @@ void ScanGroundFilterComponent::convertPointcloud( if (time_keeper_) inner_st_ptr = std::make_unique("azimuth_angle_grouping", *time_keeper_); - size_t point_index = 0; pcl::PointXYZ input_point; for (size_t data_index = 0; data_index + in_cloud_point_step <= in_cloud_data_size; data_index += in_cloud_point_step) { // Get Point - get_point_from_data_index(in_cloud, data_index, input_point); + data_accessor_.getPoint(in_cloud, data_index, input_point); // determine the azimuth angle group auto radius{static_cast(std::hypot(input_point.x, input_point.y))}; @@ -226,11 +164,10 @@ void ScanGroundFilterComponent::convertPointcloud( current_point.radius = radius; current_point.point_state = PointLabel::INIT; - current_point.orig_index = point_index; + current_point.data_index = data_index; // store the point in the corresponding radial division out_radial_ordered_points[radial_div].emplace_back(current_point); - ++point_index; } } @@ -253,332 +190,6 @@ void ScanGroundFilterComponent::calcVirtualGroundOrigin(pcl::PointXYZ & point) c point.z = 0; } -void ScanGroundFilterComponent::initializeFirstGndGrids( - const float h, const float r, const uint16_t id, std::vector & gnd_grids) const -{ - // initialize gnd_grids - gnd_grids.clear(); - gnd_grids.reserve(gnd_grid_buffer_size_); - - // Index of grids - // id is the first grid, will be filled by initial centroid_bin - // id - gnd_grid_buffer_size_ is the first grid of zero-zero position - // the intermediate grids are generated by linear interpolation - const uint16_t estimating_grid_num = gnd_grid_buffer_size_ + 1; - const uint16_t idx_estimate_from = id - estimating_grid_num; - const float gradient = h / r; - - GridCenter curr_gnd_grid; - for (uint16_t idx = 1; idx < estimating_grid_num; ++idx) { - float interpolation_ratio = static_cast(idx) / static_cast(estimating_grid_num); - const uint16_t ind_grid = idx_estimate_from + idx; - - const float interpolated_r = r * interpolation_ratio; - const float interpolated_z = gradient * interpolated_r; - - curr_gnd_grid.radius = interpolated_r; - curr_gnd_grid.avg_height = interpolated_z; - curr_gnd_grid.max_height = interpolated_z; - curr_gnd_grid.gradient = gradient; - curr_gnd_grid.intercept = 0.0f; - curr_gnd_grid.grid_id = ind_grid; - gnd_grids.push_back(curr_gnd_grid); - } -} - -void ScanGroundFilterComponent::fitLineFromGndGrid( - const std::vector & gnd_grids_list, const size_t start_idx, const size_t end_idx, - float & a, float & b) const -{ - // calculate local gradient by least square method - float sum_x = 0.0f; - float sum_y = 0.0f; - float sum_xy = 0.0f; - float sum_x2 = 0.0f; - for (auto it = gnd_grids_list.begin() + start_idx; it < gnd_grids_list.begin() + end_idx; ++it) { - sum_x += it->radius; - sum_y += it->avg_height; - sum_xy += it->radius * it->avg_height; - sum_x2 += it->radius * it->radius; - } - const float n = static_cast(end_idx - start_idx); - - // y = a * x + b - a = (n * sum_xy - sum_x * sum_y) / (n * sum_x2 - sum_x * sum_x); - b = (sum_y - a * sum_x) / n; -} - -void ScanGroundFilterComponent::checkContinuousGndGrid( - PointData & pd, const pcl::PointXYZ & point_curr, - const std::vector & gnd_grids_list) const -{ - // 1. check local slope - { - // reference gird is the last-1 - const auto reference_grid_it = gnd_grids_list.end() - 2; - const float delta_z = point_curr.z - reference_grid_it->avg_height; - const float delta_radius = pd.radius - reference_grid_it->radius; - const float local_slope_ratio = delta_z / delta_radius; - - if (abs(local_slope_ratio) < local_slope_max_ratio_) { - pd.point_state = PointLabel::GROUND; - return; - } - } - - // 2. mean of grid buffer(filtering) - const float gradient = - std::clamp(gnd_grids_list.back().gradient, -global_slope_max_ratio_, global_slope_max_ratio_); - const float & intercept = gnd_grids_list.back().intercept; - - // extrapolate next ground height - const float next_gnd_z = gradient * pd.radius + intercept; - - // calculate fixed angular threshold from the reference position - const float gnd_z_local_thresh = - std::tan(DEG2RAD(5.0)) * (pd.radius - gnd_grids_list.back().radius); - - if (abs(point_curr.z - next_gnd_z) <= non_ground_height_threshold_ + gnd_z_local_thresh) { - pd.point_state = PointLabel::GROUND; - return; - } - if (point_curr.z - next_gnd_z >= non_ground_height_threshold_ + gnd_z_local_thresh) { - pd.point_state = PointLabel::NON_GROUND; - return; - } -} - -void ScanGroundFilterComponent::checkDiscontinuousGndGrid( - PointData & pd, const pcl::PointXYZ & point_curr, - const std::vector & gnd_grids_list) const -{ - const auto & grid_ref = gnd_grids_list.back(); - const float delta_avg_z = point_curr.z - grid_ref.avg_height; - if (abs(delta_avg_z) < non_ground_height_threshold_) { - pd.point_state = PointLabel::GROUND; - return; - } - const float delta_max_z = point_curr.z - grid_ref.max_height; - if (abs(delta_max_z) < non_ground_height_threshold_) { - pd.point_state = PointLabel::GROUND; - return; - } - const float delta_radius = pd.radius - grid_ref.radius; - const float local_slope_ratio = delta_avg_z / delta_radius; - if (abs(local_slope_ratio) < local_slope_max_ratio_) { - pd.point_state = PointLabel::GROUND; - return; - } - if (local_slope_ratio >= local_slope_max_ratio_) { - pd.point_state = PointLabel::NON_GROUND; - return; - } -} - -void ScanGroundFilterComponent::checkBreakGndGrid( - PointData & pd, const pcl::PointXYZ & point_curr, - const std::vector & gnd_grids_list) const -{ - const auto & grid_ref = gnd_grids_list.back(); - const float delta_avg_z = point_curr.z - grid_ref.avg_height; - const float delta_radius = pd.radius - grid_ref.radius; - const float local_slope_ratio = delta_avg_z / delta_radius; - if (abs(local_slope_ratio) < global_slope_max_ratio_) { - pd.point_state = PointLabel::GROUND; - return; - } - if (local_slope_ratio >= global_slope_max_ratio_) { - pd.point_state = PointLabel::NON_GROUND; - return; - } -} - -void ScanGroundFilterComponent::recheckGroundCluster( - const PointsCentroid & gnd_cluster, const float non_ground_threshold, const bool use_lowest_point, - pcl::PointIndices & non_ground_indices) const -{ - const float reference_height = - use_lowest_point ? gnd_cluster.getMinHeight() : gnd_cluster.getAverageHeight(); - const pcl::PointIndices & gnd_indices = gnd_cluster.getIndicesRef(); - const std::vector & height_list = gnd_cluster.getHeightListRef(); - for (size_t i = 0; i < height_list.size(); ++i) { - if (height_list.at(i) >= reference_height + non_ground_threshold) { - non_ground_indices.indices.push_back(gnd_indices.indices.at(i)); - } - } -} - -void ScanGroundFilterComponent::classifyPointCloudGridScan( - const PointCloud2ConstPtr & in_cloud, - const std::vector & in_radial_ordered_clouds, - pcl::PointIndices & out_no_ground_indices) const -{ - std::unique_ptr st_ptr; - if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); - - out_no_ground_indices.indices.clear(); - - // run the classification algorithm for each ray (azimuth division) - for (size_t i = 0; i < in_radial_ordered_clouds.size(); ++i) { - PointsCentroid centroid_bin; - centroid_bin.initialize(); - std::vector gnd_grids; - - // check empty ray - if (in_radial_ordered_clouds[i].size() == 0) { - continue; - } - - bool initialized_first_gnd_grid = false; - - PointData pd_curr, pd_prev; - pcl::PointXYZ point_curr, point_prev; - - // initialize the previous point - { - pd_curr = in_radial_ordered_clouds[i][0]; - const size_t data_index = in_cloud->point_step * pd_curr.orig_index; - get_point_from_data_index(in_cloud, data_index, point_curr); - } - - // iterate over the points in the ray - for (const auto & point : in_radial_ordered_clouds[i]) { - // set the previous point - pd_prev = pd_curr; - point_prev = point_curr; - - // set the current point - pd_curr = point; - const size_t data_index = in_cloud->point_step * pd_curr.orig_index; - get_point_from_data_index(in_cloud, data_index, point_curr); - - // determine if the current point is in new grid - const bool is_curr_in_next_grid = pd_curr.grid_id > pd_prev.grid_id; - - // initialization process for the first grid and interpolate the previous grids - if (!initialized_first_gnd_grid) { - // set the thresholds - const float global_slope_ratio_p = point_prev.z / pd_prev.radius; - float non_ground_height_threshold_local = non_ground_height_threshold_; - if (point_prev.x < low_priority_region_x_) { - non_ground_height_threshold_local = - non_ground_height_threshold_ * abs(point_prev.x / low_priority_region_x_); - } - // non_ground_height_threshold_local is only for initialization - - // prepare centroid_bin for the first grid - if ( - // classify previous point - global_slope_ratio_p >= global_slope_max_ratio_ && - point_prev.z > non_ground_height_threshold_local) { - out_no_ground_indices.indices.push_back(pd_prev.orig_index); - pd_prev.point_state = PointLabel::NON_GROUND; - } else if ( - abs(global_slope_ratio_p) < global_slope_max_ratio_ && - abs(point_prev.z) < non_ground_height_threshold_local) { - centroid_bin.addPoint(pd_prev.radius, point_prev.z, pd_prev.orig_index); - pd_prev.point_state = PointLabel::GROUND; - // centroid_bin is filled at least once - // if the current point is in the next gird, it is ready to be initialized - initialized_first_gnd_grid = is_curr_in_next_grid; - } - // keep filling the centroid_bin until it is ready to be initialized - if (!initialized_first_gnd_grid) { - continue; - } - // estimate previous grids by linear interpolation - float h = centroid_bin.getAverageHeight(); - float r = centroid_bin.getAverageRadius(); - initializeFirstGndGrids(h, r, pd_prev.grid_id, gnd_grids); - } - - // finalize the current centroid_bin and update the gnd_grids - if (is_curr_in_next_grid && centroid_bin.getIndicesRef().indices.size() > 0) { - // check if the prev grid have ground point cloud - if (use_recheck_ground_cluster_) { - recheckGroundCluster( - centroid_bin, non_ground_height_threshold_, use_lowest_point_, out_no_ground_indices); - // centroid_bin is not modified. should be rechecked by out_no_ground_indices? - } - // convert the centroid_bin to grid-center and add it to the gnd_grids - GridCenter curr_gnd_grid; - curr_gnd_grid.radius = centroid_bin.getAverageRadius(); - curr_gnd_grid.avg_height = centroid_bin.getAverageHeight(); - curr_gnd_grid.max_height = centroid_bin.getMaxHeight(); - curr_gnd_grid.grid_id = pd_prev.grid_id; - curr_gnd_grid.gradient = 0.0f; // not calculated yet - curr_gnd_grid.intercept = 0.0f; // not calculated yet - gnd_grids.push_back(curr_gnd_grid); - // clear the centroid_bin - centroid_bin.initialize(); - - // calculate local ground gradient - float gradient, intercept; - fitLineFromGndGrid( - gnd_grids, gnd_grids.size() - gnd_grid_buffer_size_, gnd_grids.size(), gradient, - intercept); - // update the current grid - gnd_grids.back().gradient = gradient; // update the gradient - gnd_grids.back().intercept = intercept; // update the intercept - } - - // 0: set the thresholds - const float global_slope_ratio_p = point_curr.z / pd_curr.radius; - const auto & grid_ref = gnd_grids.back(); - - // 1: height is out-of-range - if (point_curr.z - grid_ref.avg_height > detection_range_z_max_) { - pd_curr.point_state = PointLabel::OUT_OF_RANGE; - continue; - } - - // 2: continuously non-ground - float points_xy_distance_square = - (point_curr.x - point_prev.x) * (point_curr.x - point_prev.x) + - (point_curr.y - point_prev.y) * (point_curr.y - point_prev.y); - if ( - pd_prev.point_state == PointLabel::NON_GROUND && - points_xy_distance_square < split_points_distance_tolerance_square_ && - point_curr.z > point_prev.z) { - pd_curr.point_state = PointLabel::NON_GROUND; - out_no_ground_indices.indices.push_back(pd_curr.orig_index); - continue; - } - - // 3: the angle is exceed the global slope threshold - if (global_slope_ratio_p > global_slope_max_ratio_) { - out_no_ground_indices.indices.push_back(pd_curr.orig_index); - continue; - } - - const uint16_t next_gnd_grid_id_thresh = (gnd_grids.end() - gnd_grid_buffer_size_)->grid_id + - gnd_grid_buffer_size_ + gnd_grid_continual_thresh_; - const float curr_grid_width = grid_.getGridSize(pd_curr.radius, pd_curr.grid_id); - if ( - // 4: the point is continuous with the previous grid - pd_curr.grid_id < next_gnd_grid_id_thresh && - pd_curr.radius - grid_ref.radius < gnd_grid_continual_thresh_ * curr_grid_width) { - checkContinuousGndGrid(pd_curr, point_curr, gnd_grids); - } else if ( - // 5: the point is discontinuous with the previous grid - pd_curr.radius - grid_ref.radius < gnd_grid_continual_thresh_ * curr_grid_width) { - checkDiscontinuousGndGrid(pd_curr, point_curr, gnd_grids); - } else { - // 6: the point is break the previous grid - checkBreakGndGrid(pd_curr, point_curr, gnd_grids); - } - - // update the point label and update the ground cluster - if (pd_curr.point_state == PointLabel::NON_GROUND) { - out_no_ground_indices.indices.push_back(pd_curr.orig_index); - } else if (pd_curr.point_state == PointLabel::GROUND) { - centroid_bin.addPoint(pd_curr.radius, point_curr.z, pd_curr.orig_index); - } - // else, the point is not classified - } - } -} - void ScanGroundFilterComponent::classifyPointCloud( const PointCloud2ConstPtr & in_cloud, const std::vector & in_radial_ordered_clouds, @@ -615,8 +226,7 @@ void ScanGroundFilterComponent::classifyPointCloud( const PointData & pd = in_radial_ordered_clouds[i][j]; point_label_curr = pd.point_state; - const size_t data_index = in_cloud->point_step * pd.orig_index; - get_point_from_data_index(in_cloud, data_index, point_curr); + data_accessor_.getPoint(in_cloud, pd.data_index, point_curr); if (j == 0) { bool is_front_side = (point_curr.x > virtual_ground_point.x); if (use_virtual_ground_point_ && is_front_side) { @@ -677,12 +287,12 @@ void ScanGroundFilterComponent::classifyPointCloud( non_ground_cluster.initialize(); } if (point_label_curr == PointLabel::NON_GROUND) { - out_no_ground_indices.indices.push_back(pd.orig_index); + out_no_ground_indices.indices.push_back(pd.data_index); } else if ( // NOLINT (point_label_prev == PointLabel::NON_GROUND) && (point_label_curr == PointLabel::POINT_FOLLOW)) { point_label_curr = PointLabel::NON_GROUND; - out_no_ground_indices.indices.push_back(pd.orig_index); + out_no_ground_indices.indices.push_back(pd.data_index); } else if ( // NOLINT (point_label_prev == PointLabel::GROUND) && (point_label_curr == PointLabel::POINT_FOLLOW)) { @@ -714,9 +324,9 @@ void ScanGroundFilterComponent::extractObjectPoints( size_t output_data_size = 0; - for (const auto & i : in_indices.indices) { + for (const auto & idx : in_indices.indices) { std::memcpy( - &out_object_cloud.data[output_data_size], &in_cloud_ptr->data[i * in_cloud_ptr->point_step], + &out_object_cloud.data[output_data_size], &in_cloud_ptr->data[idx], in_cloud_ptr->point_step * sizeof(uint8_t)); output_data_size += in_cloud_ptr->point_step; } @@ -731,19 +341,19 @@ void ScanGroundFilterComponent::faster_filter( if (time_keeper_) st_ptr = std::make_unique(__func__, *time_keeper_); std::scoped_lock lock(mutex_); - stop_watch_ptr_->toc("processing_time", true); + if (stop_watch_ptr_) stop_watch_ptr_->toc("processing_time", true); - if (!data_offset_initialized_) { - set_field_index_offsets(input); + if (!data_accessor_.isInitialized()) { + data_accessor_.setField(input); + grid_ground_filter_ptr_->setDataAccessor(input); } - std::vector radial_ordered_points; pcl::PointIndices no_ground_indices; if (elevation_grid_mode_) { - convertPointcloudGridScan(input, radial_ordered_points); - classifyPointCloudGridScan(input, radial_ordered_points, no_ground_indices); + grid_ground_filter_ptr_->process(input, no_ground_indices); } else { + std::vector radial_ordered_points; convertPointcloud(input, radial_ordered_points); classifyPointCloud(input, radial_ordered_points, no_ground_indices); } @@ -783,10 +393,10 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter( const std::vector & param) { if (get_param(param, "grid_size_m", grid_size_m_)) { - grid_.initialize(grid_size_m_, grid_mode_switch_radius_, virtual_lidar_z_); + // grid_ptr_->initialize(grid_size_m_, radial_divider_angle_rad_, grid_mode_switch_radius_); } if (get_param(param, "grid_mode_switch_radius", grid_mode_switch_radius_)) { - grid_.initialize(grid_size_m_, grid_mode_switch_radius_, virtual_lidar_z_); + // grid_ptr_->initialize(grid_size_m_, radial_divider_angle_rad_, grid_mode_switch_radius_); } double global_slope_max_angle_deg{get_parameter("global_slope_max_angle_deg").as_double()}; if (get_param(param, "global_slope_max_angle_deg", global_slope_max_angle_deg)) { @@ -808,19 +418,15 @@ rcl_interfaces::msg::SetParametersResult ScanGroundFilterComponent::onParameter( if (get_param(param, "radial_divider_angle_deg", radial_divider_angle_deg)) { radial_divider_angle_rad_ = deg2rad(radial_divider_angle_deg); radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_); + // grid_ptr_->initialize(grid_size_m_, radial_divider_angle_rad_, grid_mode_switch_radius_); RCLCPP_DEBUG( get_logger(), "Setting radial_divider_angle_rad to: %f.", radial_divider_angle_rad_); RCLCPP_DEBUG(get_logger(), "Setting radial_dividers_num to: %zu.", radial_dividers_num_); } if (get_param(param, "split_points_distance_tolerance", split_points_distance_tolerance_)) { - split_points_distance_tolerance_square_ = - split_points_distance_tolerance_ * split_points_distance_tolerance_; RCLCPP_DEBUG( get_logger(), "Setting split_points_distance_tolerance to: %f.", split_points_distance_tolerance_); - RCLCPP_DEBUG( - get_logger(), "Setting split_points_distance_tolerance_square to: %f.", - split_points_distance_tolerance_square_); } if (get_param(param, "split_height_distance", split_height_distance_)) { RCLCPP_DEBUG(get_logger(), "Setting split_height_distance to: %f.", split_height_distance_); 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 acc6114ed0acc..62db8307a0a37 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp @@ -15,11 +15,13 @@ #ifndef SCAN_GROUND_FILTER__NODE_HPP_ #define SCAN_GROUND_FILTER__NODE_HPP_ -#include "autoware/pointcloud_preprocessor/filter.hpp" -#include "autoware/pointcloud_preprocessor/transform_info.hpp" -#include "autoware/universe_utils/system/time_keeper.hpp" -#include "autoware_vehicle_info_utils/vehicle_info.hpp" -#include "grid.hpp" +#include "data.hpp" +#include "grid_ground_filter.hpp" + +#include +#include +#include +#include #include @@ -36,6 +38,7 @@ #include +#include #include #include #include @@ -67,20 +70,10 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt float radius; // cylindrical coords on XY Plane PointLabel point_state{PointLabel::INIT}; uint16_t grid_id; // id of grid in vertical - size_t orig_index; // index of this point in the source pointcloud + size_t data_index; // index of this point data in the source pointcloud }; using PointCloudVector = std::vector; - struct GridCenter - { - float radius; - float avg_height; - float max_height; - float gradient; - float intercept; - uint16_t grid_id; - }; - struct PointsCentroid { float radius_sum; @@ -91,8 +84,9 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt float height_min; uint32_t point_num; uint16_t grid_id; - pcl::PointIndices pcl_indices; + std::vector pcl_indices; std::vector height_list; + std::vector radius_list; PointsCentroid() : radius_sum(0.0f), @@ -116,7 +110,7 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt height_min = 10.0f; point_num = 0; grid_id = 0; - pcl_indices.indices.clear(); + pcl_indices.clear(); height_list.clear(); } @@ -130,24 +124,20 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt height_max = height_max < height ? height : height_max; height_min = height_min > height ? height : height_min; } - void addPoint(const float radius, const float height, const uint index) + + void addPoint(const float radius, const float height, const size_t index) { - pcl_indices.indices.push_back(index); + pcl_indices.push_back(index); height_list.push_back(height); addPoint(radius, height); } float getAverageSlope() const { return std::atan2(height_avg, radius_avg); } - float getAverageHeight() const { return height_avg; } - float getAverageRadius() const { return radius_avg; } - float getMaxHeight() const { return height_max; } - float getMinHeight() const { return height_min; } - - const pcl::PointIndices & getIndicesRef() const { return pcl_indices; } + const std::vector & getIndicesRef() const { return pcl_indices; } const std::vector & getHeightListRef() const { return height_list; } }; @@ -163,12 +153,8 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt tf2_ros::Buffer tf_buffer_{get_clock()}; tf2_ros::TransformListener tf_listener_{tf_buffer_}; - int data_offset_x_; - int data_offset_y_; - int data_offset_z_; - int data_offset_intensity_; - int intensity_type_; - bool data_offset_initialized_; + // data accessor + PclDataAccessor data_accessor_; const uint16_t gnd_grid_continual_thresh_ = 3; bool elevation_grid_mode_; @@ -187,7 +173,6 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt float global_slope_max_ratio_; float local_slope_max_ratio_; float split_points_distance_tolerance_; // distance in meters between concentric divisions - float split_points_distance_tolerance_square_; // non-grid mode parameters bool use_virtual_ground_point_; @@ -206,13 +191,8 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt uint16_t gnd_grid_buffer_size_; float virtual_lidar_z_; - // grid data - ScanGroundGrid grid_; - - // data access methods - void set_field_index_offsets(const PointCloud2ConstPtr & input); - void get_point_from_data_index( - const PointCloud2ConstPtr & input, const size_t data_index, pcl::PointXYZ & point) const; + // grid ground filter processor + std::unique_ptr grid_ground_filter_ptr_; // time keeper related rclcpp::Publisher::SharedPtr @@ -237,9 +217,7 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt void convertPointcloud( const PointCloud2ConstPtr & in_cloud, std::vector & out_radial_ordered_points) const; - void convertPointcloudGridScan( - const PointCloud2ConstPtr & in_cloud, - std::vector & out_radial_ordered_points) const; + /*! * Output ground center of front wheels as the virtual ground point * @param[out] point Virtual ground origin point @@ -253,39 +231,10 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt * @param out_no_ground_indices Returns the indices of the points * classified as not ground in the original PointCloud */ - - void initializeFirstGndGrids( - const float h, const float r, const uint16_t id, std::vector & gnd_grids) const; - - void fitLineFromGndGrid( - const std::vector & gnd_grids_list, const size_t start_idx, const size_t end_idx, - float & a, float & b) const; - void checkContinuousGndGrid( - PointData & pd, const pcl::PointXYZ & point_curr, - const std::vector & gnd_grids_list) const; - void checkDiscontinuousGndGrid( - PointData & pd, const pcl::PointXYZ & point_curr, - const std::vector & gnd_grids_list) const; - void checkBreakGndGrid( - PointData & pd, const pcl::PointXYZ & point_curr, - const std::vector & gnd_grids_list) const; void classifyPointCloud( const PointCloud2ConstPtr & in_cloud, const std::vector & in_radial_ordered_clouds, pcl::PointIndices & out_no_ground_indices) const; - void classifyPointCloudGridScan( - const PointCloud2ConstPtr & in_cloud, - const std::vector & in_radial_ordered_clouds, - pcl::PointIndices & out_no_ground_indices) const; - /*! - * Re-classifies point of ground cluster based on their height - * @param gnd_cluster Input ground cluster for re-checking - * @param non_ground_threshold Height threshold for ground and non-ground points classification - * @param non_ground_indices Output non-ground PointCloud indices - */ - void recheckGroundCluster( - const PointsCentroid & gnd_cluster, const float non_ground_threshold, - const bool use_lowest_point, pcl::PointIndices & non_ground_indices) const; /*! * Returns the resulting complementary PointCloud, one with the points kept * and the other removed as indicated in the indices From f3e76a8affaaa67e4edcdadff1a4ea74dad1b67a Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 26 Nov 2024 09:11:52 +0900 Subject: [PATCH 111/273] fix(surround_obstacle_checker)!: remove stop reason (#9450) fix(surround_obstacle_checker): remove stop reason Signed-off-by: satoshi-ota --- .../README.md | 3 -- .../surround_obstacle_checker.launch.xml | 1 - .../src/debug_marker.cpp | 30 ----------------- .../src/debug_marker.hpp | 6 ---- .../src/node.cpp | 33 ------------------- .../src/node.hpp | 1 - .../surround_obstacle_checker-design.ja.md | 3 -- 7 files changed, 77 deletions(-) diff --git a/planning/autoware_surround_obstacle_checker/README.md b/planning/autoware_surround_obstacle_checker/README.md index 1f4bf77145624..fbe749f2eec08 100644 --- a/planning/autoware_surround_obstacle_checker/README.md +++ b/planning/autoware_surround_obstacle_checker/README.md @@ -34,8 +34,6 @@ else endif -:Publish stop reason; - stop @enduml ``` @@ -93,7 +91,6 @@ As mentioned in stop condition section, it prevents chattering by changing thres | `~/output/velocity_limit_clear_command` | `tier4_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command | | `~/output/max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | Velocity limit command | | `~/output/no_start_reason` | `diagnostic_msgs::msg::DiagnosticStatus` | No start reason | -| `~/output/stop_reasons` | `tier4_planning_msgs::msg::StopReasonArray` | Stop reasons | | `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization | | `~/debug/footprint` | `geometry_msgs::msg::PolygonStamped` | Ego vehicle base footprint for visualization | | `~/debug/footprint_offset` | `geometry_msgs::msg::PolygonStamped` | Ego vehicle footprint with `surround_check_distance` offset for visualization | diff --git a/planning/autoware_surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml b/planning/autoware_surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml index 0ba7d29090916..c7e440f6eb3e1 100644 --- a/planning/autoware_surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml +++ b/planning/autoware_surround_obstacle_checker/launch/surround_obstacle_checker.launch.xml @@ -10,7 +10,6 @@ - diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp index 57d9cc8bc67a7..6a5883fbd660d 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp @@ -75,7 +75,6 @@ SurroundObstacleCheckerDebugNode::SurroundObstacleCheckerDebugNode( clock_(clock) { debug_viz_pub_ = node.create_publisher("~/debug/marker", 1); - stop_reason_pub_ = node.create_publisher("~/output/stop_reasons", 1); velocity_factor_pub_ = node.create_publisher("/planning/velocity_factors/surround_obstacle", 1); vehicle_footprint_pub_ = node.create_publisher("~/debug/footprint", 1); @@ -142,8 +141,6 @@ void SurroundObstacleCheckerDebugNode::publish() debug_viz_pub_->publish(visualization_msg); /* publish stop reason for autoware api */ - const auto stop_reason_msg = makeStopReasonArray(); - stop_reason_pub_->publish(stop_reason_msg); const auto velocity_factor_msg = makeVelocityFactorArray(); velocity_factor_pub_->publish(velocity_factor_msg); @@ -171,33 +168,6 @@ MarkerArray SurroundObstacleCheckerDebugNode::makeVisualizationMarker() return msg; } -StopReasonArray SurroundObstacleCheckerDebugNode::makeStopReasonArray() -{ - // create header - std_msgs::msg::Header header; - header.frame_id = "map"; - header.stamp = this->clock_->now(); - - // create stop reason stamped - StopReason stop_reason_msg; - stop_reason_msg.reason = StopReason::SURROUND_OBSTACLE_CHECK; - StopFactor stop_factor; - - if (stop_pose_ptr_ != nullptr) { - stop_factor.stop_pose = *stop_pose_ptr_; - if (stop_obstacle_point_ptr_ != nullptr) { - stop_factor.stop_factor_points.emplace_back(*stop_obstacle_point_ptr_); - } - stop_reason_msg.stop_factors.emplace_back(stop_factor); - } - - // create stop reason array - StopReasonArray stop_reason_array; - stop_reason_array.header = header; - stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); - return stop_reason_array; -} - VelocityFactorArray SurroundObstacleCheckerDebugNode::makeVelocityFactorArray() { VelocityFactorArray velocity_factor_array; diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp index 17ec2631b2dad..b2c350c1b4698 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.hpp @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -39,9 +38,6 @@ using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using geometry_msgs::msg::PolygonStamped; -using tier4_planning_msgs::msg::StopFactor; -using tier4_planning_msgs::msg::StopReason; -using tier4_planning_msgs::msg::StopReasonArray; using visualization_msgs::msg::Marker; using visualization_msgs::msg::MarkerArray; @@ -69,7 +65,6 @@ class SurroundObstacleCheckerDebugNode private: rclcpp::Publisher::SharedPtr debug_viz_pub_; - rclcpp::Publisher::SharedPtr stop_reason_pub_; rclcpp::Publisher::SharedPtr velocity_factor_pub_; rclcpp::Publisher::SharedPtr vehicle_footprint_pub_; @@ -85,7 +80,6 @@ class SurroundObstacleCheckerDebugNode geometry_msgs::msg::Pose self_pose_; MarkerArray makeVisualizationMarker(); - StopReasonArray makeStopReasonArray(); VelocityFactorArray makeVelocityFactorArray(); PolygonStamped boostPolygonToPolygonStamped(const Polygon2d & boost_polygon, const double & z); diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index 70e81fa3b1d12..1a938a9275df5 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -57,34 +57,6 @@ using autoware::universe_utils::createPoint; using autoware::universe_utils::pose2transform; using autoware_perception_msgs::msg::ObjectClassification; -namespace -{ -std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose) -{ - const std::string json_dumps_pose = - (boost::format( - R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") % - pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x % - pose.orientation.y % pose.orientation.z) - .str(); - return json_dumps_pose; -} - -diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( - const std::string & no_start_reason, const geometry_msgs::msg::Pose & stop_pose) -{ - diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; - diagnostic_msgs::msg::KeyValue no_start_reason_diag_kv; - no_start_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - no_start_reason_diag.name = "no_start_reason"; - no_start_reason_diag.message = no_start_reason; - no_start_reason_diag_kv.key = "no_start_pose"; - no_start_reason_diag_kv.value = jsonDumpsPose(stop_pose); - no_start_reason_diag.values.push_back(no_start_reason_diag_kv); - return no_start_reason_diag; -} -} // namespace - SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptions & node_options) : Node("surround_obstacle_checker_node", node_options) { @@ -104,8 +76,6 @@ SurroundObstacleCheckerNode::SurroundObstacleCheckerNode(const rclcpp::NodeOptio vehicle_info_ = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); // Publishers - pub_stop_reason_ = - this->create_publisher("~/output/no_start_reason", 1); pub_clear_velocity_limit_ = this->create_publisher( "~/output/velocity_limit_clear_command", rclcpp::QoS{1}.transient_local()); pub_velocity_limit_ = this->create_publisher( @@ -256,10 +226,8 @@ void SurroundObstacleCheckerNode::onTimer() debug_ptr_->pushObstaclePoint(nearest_obstacle.value().second, PointType::NoStart); } - diagnostic_msgs::msg::DiagnosticStatus no_start_reason_diag; if (state_ == State::STOP) { debug_ptr_->pushPose(odometry_ptr_->pose.pose, PoseType::NoStart); - no_start_reason_diag = makeStopReasonDiag("obstacle", odometry_ptr_->pose.pose); } tier4_debug_msgs::msg::Float64Stamped processing_time_msg; @@ -267,7 +235,6 @@ void SurroundObstacleCheckerNode::onTimer() processing_time_msg.data = stop_watch.toc(); pub_processing_time_->publish(processing_time_msg); - pub_stop_reason_->publish(no_start_reason_diag); debug_ptr_->publish(); } diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index 480a937a4a909..17eb2979e6809 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -104,7 +104,6 @@ class SurroundObstacleCheckerNode : public rclcpp::Node sub_pointcloud_{this, "~/input/pointcloud", autoware::universe_utils::SingleDepthSensorQoS()}; autoware::universe_utils::InterProcessPollingSubscriber sub_dynamic_objects_{ this, "~/input/objects"}; - rclcpp::Publisher::SharedPtr pub_stop_reason_; rclcpp::Publisher::SharedPtr pub_clear_velocity_limit_; rclcpp::Publisher::SharedPtr pub_velocity_limit_; rclcpp::Publisher::SharedPtr pub_processing_time_; diff --git a/planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja.md b/planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja.md index f8a5f29e064f7..b19f556e59830 100644 --- a/planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja.md +++ b/planning/autoware_surround_obstacle_checker/surround_obstacle_checker-design.ja.md @@ -34,8 +34,6 @@ else endif -:Publish stop reason; - stop @enduml ``` @@ -93,7 +91,6 @@ Stop condition の項で述べたように、状態によって障害物判定 | `~/output/velocity_limit_clear_command` | `tier4_planning_msgs::msg::VelocityLimitClearCommand` | Velocity limit clear command | | `~/output/max_velocity` | `tier4_planning_msgs::msg::VelocityLimit` | Velocity limit command | | `~/output/no_start_reason` | `diagnostic_msgs::msg::DiagnosticStatus` | No start reason | -| `~/output/stop_reasons` | `tier4_planning_msgs::msg::StopReasonArray` | Stop reasons | | `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization | ## Parameters From e46e2fcf68d057b7502c7ffbd66ee350774e58a3 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 09:13:46 +0900 Subject: [PATCH 112/273] fix(tier4_camera_view_rviz_plugin): fix clang-diagnostic-unused-const-variable (#9438) Signed-off-by: veqcc --- .../src/bird_eye_view_controller.cpp | 3 --- .../src/third_person_view_controller.cpp | 1 - 2 files changed, 4 deletions(-) diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp index b6637a3c619a5..a961d7c9250ce 100644 --- a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp +++ b/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp @@ -62,9 +62,6 @@ static const Ogre::Quaternion ROBOT_TO_CAMERA_ROTATION = Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Y) * Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), Ogre::Vector3::UNIT_Z); -static const float PITCH_LIMIT_LOW = -Ogre::Math::HALF_PI + 0.001; -static const float PITCH_LIMIT_HIGH = Ogre::Math::HALF_PI - 0.001; - BirdEyeViewController::BirdEyeViewController() : dragging_(false) { scale_property_ = new rviz_common::properties::FloatProperty( diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp b/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp index 97216f238d593..b7d754b02d4bd 100644 --- a/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp +++ b/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp @@ -68,7 +68,6 @@ static const float PITCH_START = Ogre::Math::HALF_PI / 3; static const float YAW_START = Ogre::Math::PI; static const float DISTANCE_START = 30; static const float FOCAL_SHAPE_SIZE_START = 0.05; -static const bool FOCAL_SHAPE_FIXED_SIZE = true; static const char * TARGET_FRAME_START = "base_link"; // move camera up so the focal point appears in the lower image half From 19364ff11980e4e390dc429ac944cb1a2590cf58 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 10:11:15 +0900 Subject: [PATCH 113/273] fix(autoware_vehicle_cmd_gate): remove unused variable (#9377) Signed-off-by: veqcc --- control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp index 9e5db63f9311d..c44e96631998f 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.hpp @@ -137,7 +137,6 @@ class VehicleCmdGate : public rclcpp::Node bool is_engaged_; bool is_system_emergency_ = false; bool is_external_emergency_stop_ = false; - bool is_filtered_marker_published_ = false; double current_steer_ = 0; GateMode current_gate_mode_; MrmState current_mrm_state_; From 0db25c101dd1729918217ae13e9575a4b87042d4 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 13:34:51 +0900 Subject: [PATCH 114/273] fix(diagnostic_graph_utils): fix clang-diagnostic-delete-abstract-non-virtual-dtor (#9431) Signed-off-by: veqcc --- .../include/diagnostic_graph_utils/graph.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp index c5b386dbe2c86..275e4ffcb1c7e 100644 --- a/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp +++ b/system/diagnostic_graph_utils/include/diagnostic_graph_utils/graph.hpp @@ -37,6 +37,8 @@ class DiagUnit using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus; using DiagnosticLevel = DiagnosticStatus::_level_type; + virtual ~DiagUnit() = default; + struct DiagChild { DiagLink * link; From b3ded07cbf31bb3947f8d240fa83d27f1287d9ca Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Tue, 26 Nov 2024 13:40:48 +0900 Subject: [PATCH 115/273] feat(processing_time_checker): update processing time list (#9350) Signed-off-by: Kasunori-Nakajima --- .../config/processing_time_checker.param.yaml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/system/autoware_processing_time_checker/config/processing_time_checker.param.yaml b/system/autoware_processing_time_checker/config/processing_time_checker.param.yaml index 033b20d234fd9..526e413ea196f 100644 --- a/system/autoware_processing_time_checker/config/processing_time_checker.param.yaml +++ b/system/autoware_processing_time_checker/config/processing_time_checker.param.yaml @@ -2,6 +2,7 @@ ros__parameters: update_rate: 10.0 processing_time_topic_name_list: + - /control/control_evaluator/debug/processing_time_ms - /control/control_validator/debug/processing_time_ms - /control/trajectory_follower/controller_node_exe/lateral/debug/processing_time_ms - /control/trajectory_follower/controller_node_exe/longitudinal/debug/processing_time_ms @@ -9,6 +10,9 @@ - /control/vehicle_cmd_gate/debug/processing_time_ms - /perception/object_recognition/prediction/map_based_prediction/debug/processing_time_ms - /perception/object_recognition/tracking/multi_object_tracker/debug/processing_time_ms + - /planning/mission_planning/mission_planner/debug/processing_time_ms + - /planning/mission_planning/route_selector/debug/processing_time_ms + - /planning/planning_evaluator/debug/processing_time_ms - /planning/planning_validator/debug/processing_time_ms - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance_by_lane_change/processing_time_ms - /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/dynamic_obstacle_avoidance/processing_time_ms @@ -37,6 +41,7 @@ - /planning/scenario_planning/lane_driving/motion_planning/path_optimizer/debug/processing_time_ms - /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/processing_time_ms - /planning/scenario_planning/parking/costmap_generator/debug/processing_time_ms + - /planning/scenario_planning/parking/freespace_planner/debug/processing_time_ms - /planning/scenario_planning/scenario_selector/debug/processing_time_ms - /planning/scenario_planning/velocity_smoother/debug/processing_time_ms - /simulation/shape_estimation/debug/processing_time_ms From abf0f23c6a66cacf7a302c51b49cbcdaa165b3bd Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Tue, 26 Nov 2024 14:10:21 +0900 Subject: [PATCH 116/273] refactor(lane_change): refactor lane change parameters (#9403) * refactor lane change parameters Signed-off-by: mohammad alqudah * update lane change param yaml Signed-off-by: mohammad alqudah * update lane change README Signed-off-by: mohammad alqudah * regroup some parameters Signed-off-by: mohammad alqudah * run pre-commit prettier step Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * apply pre-commit checks Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --- .../README.md | 41 +- .../config/lane_change.param.yaml | 51 +-- .../utils/data_structs.hpp | 135 +----- .../utils/parameters.hpp | 169 ++++++++ .../src/manager.cpp | 398 ++++++++---------- .../src/scene.cpp | 92 ++-- .../src/utils/calculation.cpp | 52 +-- .../src/utils/utils.cpp | 18 +- 8 files changed, 475 insertions(+), 481 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp 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 3b23dd8b4212b..6ebe79c180e95 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 @@ -525,8 +525,6 @@ The ego vehicle may need to secure ample inter-vehicle distance ahead of the tar ![enable collision check at prepare phase](./images/lane_change-enable_collision_check_at_prepare_phase.png) -The parameter `prepare_phase_ignore_target_speed_thresh` can be configured to ignore the prepare phase collision check for targets whose speeds are less than a specific threshold, such as stationary or very slow-moving objects. - #### If the lane is blocked and multiple lane changes When driving on the public road with other vehicles, there exist scenarios where lane changes cannot be executed. Suppose the candidate path is evaluated as unsafe, for example, due to incoming vehicles in the adjacent lane. In that case, the ego vehicle can't change lanes, and it is impossible to reach the goal. Therefore, the ego vehicle must stop earlier at a certain distance and wait for the adjacent lane to be evaluated as safe. The minimum stopping distance can be computed from shift length and minimum lane changing velocity. @@ -820,25 +818,22 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | Name | Unit | Type | Description | Default value | | :------------------------------------------- | ------ | ------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------ | | `backward_lane_length` | [m] | double | The backward length to check incoming objects in lane change target lane. | 200.0 | -| `prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | | `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 | | `backward_length_from_intersection` | [m] | double | Distance threshold from the last intersection to invalidate or cancel the lane change path | 5.0 | -| `lane_change_finish_judge_buffer` | [m] | double | The additional buffer used to confirm lane change process completion | 2.0 | -| `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 | -| `longitudinal_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 3 | -| `lateral_acceleration_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | +| `trajectory.prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | +| `trajectory.lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | +| `trajectory.minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | +| `trajectory.lon_acc_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 3 | +| `trajectory.lat_acc_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | +| `trajectory.max_longitudinal_acc` | [m/s2] | double | maximum longitudinal acceleration for lane change | 1.0 | +| `trajectory.min_longitudinal_acc` | [m/s2] | double | maximum longitudinal deceleration for lane change | -1.0 | | `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | | `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | | `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | -| `length_ratio_for_turn_signal_deactivation` | [-] | double | Turn signal will be deactivated if the ego vehicle approaches to this length ratio for lane change finish point | 0.8 | -| `max_longitudinal_acc` | [-] | double | maximum longitudinal acceleration for lane change | 1.0 | -| `min_longitudinal_acc` | [-] | double | maximum longitudinal deceleration for lane change | -1.0 | | `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | -| `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] | +| `lateral_acceleration.min_values` | [m/s2] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] | +| `lateral_acceleration.max_values` | [m/s2] | 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 @@ -891,14 +886,14 @@ The following parameters are used to judge lane change completion. | Name | Unit | Type | Description | Default value | | :------------------------------------------------------- | ----- | ------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------- | -| `enable_collision_check_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false | -| `enable_collision_check_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | true | -| `enable_collision_check_for_prepare_phase.turns` | [-] | boolean | Perform collision check starting from prepare phase when ego is in lanelet with turn direction tags. If `false`, collision check only evaluated for lane changing phase. | true | -| `prepare_phase_ignore_target_speed_thresh` | [m/s] | double | Ignore collision check in prepare phase of object speed that is lesser that the configured value. `enable_collision_check_at_prepare_phase` must be `true` | 0.1 | -| `check_objects_on_current_lanes` | [-] | boolean | If true, the lane change module check objects on current lanes when performing collision assessment. | false | -| `check_objects_on_other_lanes` | [-] | boolean | If true, the lane change module include objects on other lanes. when performing collision assessment | false | -| `use_all_predicted_path` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | -| `safety_check.collision_check_yaw_diff_threshold` | [rad] | double | Maximum yaw difference between ego and object when executing rss-based collision checking | 3.1416 | +| `collision_check.enable_for_prepare_phase.general_lanes` | [-] | boolean | Perform collision check starting from the prepare phase for situations not explicitly covered by other settings (e.g., intersections). If `false`, collision check only evaluated for lane changing phase. | false | +| `collision_check.enable_for_prepare_phase.intersection` | [-] | boolean | Perform collision check starting from prepare phase when ego is in intersection. If `false`, collision check only evaluated for lane changing phase. | true | +| `collision_check.enable_for_prepare_phase.turns` | [-] | boolean | Perform collision check starting from prepare phase when ego is in lanelet with turn direction tags. If `false`, collision check only evaluated for lane changing phase. | true | +| `collision_check.check_current_lanes` | [-] | boolean | If true, the lane change module always checks objects in the current lanes for collision assessment. If false, it only checks objects in the current lanes when the ego vehicle is stuck. | false | +| `collision_check.check_other_lanes` | [-] | boolean | If true, the lane change module includes objects in other lanes when performing collision assessment. | false | +| `collision_check.use_all_predicted_paths` | [-] | boolean | If false, use only the predicted path that has the maximum confidence. | true | +| `collision_check.prediction_time_resolution` | [s] | double | Time resolution for object's path interpolation and collision check. | 0.5 | +| `collision_check.yaw_diff_threshold` | [rad] | double | Maximum yaw difference between ego and object when executing rss-based collision checking | 3.1416 | #### safety constraints during lane change path is computed @@ -910,7 +905,7 @@ The following parameters are used to judge lane change completion. | `safety_check.execution.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. | 1.0 | | `safety_check.execution.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. | 2.0 | | `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_check.execution.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 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 a2a6fbfd880e4..6ac4544f2b342 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 @@ -1,42 +1,35 @@ /**: ros__parameters: lane_change: - backward_lane_length: 200.0 #[m] - prepare_duration: 4.0 # [s] - + backward_lane_length: 200.0 backward_length_buffer_for_end_of_lane: 3.0 # [m] backward_length_buffer_for_blocking_object: 3.0 # [m] backward_length_from_intersection: 5.0 # [m] - lane_changing_lateral_jerk: 0.5 # [m/s3] - - minimum_lane_changing_velocity: 2.78 # [m/s] - prediction_time_resolution: 0.5 # [s] - longitudinal_acceleration_sampling_num: 5 - lateral_acceleration_sampling_num: 3 - # side walk parked vehicle object_check_min_road_shoulder_width: 0.5 # [m] object_shiftable_ratio_threshold: 0.6 # turn signal min_length_for_turn_signal_activation: 10.0 # [m] - length_ratio_for_turn_signal_deactivation: 0.8 # ratio (desired end position) - # longitudinal acceleration - min_longitudinal_acc: -1.0 - max_longitudinal_acc: 1.0 - - skip_process: - longitudinal_distance_diff_threshold: - prepare: 1.0 - lane_changing: 1.0 + # trajectory generation + trajectory: + prepare_duration: 4.0 + lateral_jerk: 0.5 + min_longitudinal_acc: -1.0 + max_longitudinal_acc: 1.0 + th_prepare_length_diff: 1.0 + th_lane_changing_length_diff: 1.0 + min_lane_changing_velocity: 2.78 + lon_acc_sampling_num: 5 + lat_acc_sampling_num: 3 # safety check safety_check: allow_loose_check_for_cancel: true enable_target_lane_bound_check: true - collision_check_yaw_diff_threshold: 3.1416 + stopped_object_velocity_threshold: 1.0 # [m/s] execution: expected_front_deceleration: -1.0 expected_rear_deceleration: -1.0 @@ -104,14 +97,16 @@ stop_time: 3.0 # [s] # collision check - enable_collision_check_for_prepare_phase: - general_lanes: false - intersection: true - turns: true - stopped_object_velocity_threshold: 1.0 # [m/s] - check_objects_on_current_lanes: false - check_objects_on_other_lanes: false - use_all_predicted_path: false + collision_check: + enable_for_prepare_phase: + general_lanes: false + intersection: true + turns: true + prediction_time_resolution: 0.5 + yaw_diff_threshold: 3.1416 + check_current_lanes: false + check_other_lanes: false + use_all_predicted_paths: false # lane change cancel cancel: 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 231353e812dd1..32cf000ecb1a7 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 @@ -14,6 +14,7 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ #define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_ +#include "autoware/behavior_path_lane_change_module/utils/parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" @@ -42,140 +43,6 @@ using route_handler::RouteHandler; using universe_utils::Polygon2d; using utils::path_safety_checker::ExtendedPredictedObjects; -struct LateralAccelerationMap -{ - std::vector base_vel; - std::vector base_min_acc; - std::vector base_max_acc; - - void add(const double velocity, const double min_acc, const double max_acc) - { - if (base_vel.size() != base_min_acc.size() || base_vel.size() != base_max_acc.size()) { - return; - } - - size_t idx = 0; - for (size_t i = 0; i < base_vel.size(); ++i) { - if (velocity < base_vel.at(i)) { - break; - } - idx = i + 1; - } - - base_vel.insert(base_vel.begin() + idx, velocity); - base_min_acc.insert(base_min_acc.begin() + idx, min_acc); - base_max_acc.insert(base_max_acc.begin() + idx, max_acc); - } - - std::pair find(const double velocity) const - { - if (!base_vel.empty() && velocity < base_vel.front()) { - return std::make_pair(base_min_acc.front(), base_max_acc.front()); - } - if (!base_vel.empty() && velocity > base_vel.back()) { - return std::make_pair(base_min_acc.back(), base_max_acc.back()); - } - - const double min_acc = autoware::interpolation::lerp(base_vel, base_min_acc, velocity); - const double max_acc = autoware::interpolation::lerp(base_vel, base_max_acc, velocity); - - return std::make_pair(min_acc, max_acc); - } -}; - -struct CancelParameters -{ - bool enable_on_prepare_phase{true}; - bool enable_on_lane_changing_phase{false}; - double delta_time{1.0}; - double duration{5.0}; - double max_lateral_jerk{10.0}; - double overhang_tolerance{0.0}; - - // unsafe_hysteresis_threshold will be compare with the number of detected unsafe instance. If the - // number of unsafe exceeds unsafe_hysteresis_threshold, the lane change will be cancelled or - // aborted. - int unsafe_hysteresis_threshold{2}; - - int deceleration_sampling_num{5}; -}; - -struct Parameters -{ - // trajectory generation - double backward_lane_length{200.0}; - double prediction_time_resolution{0.5}; - int longitudinal_acc_sampling_num{10}; - int lateral_acc_sampling_num{10}; - - // lane change parameters - double backward_length_buffer_for_end_of_lane{0.0}; - double backward_length_buffer_for_blocking_object{0.0}; - double backward_length_from_intersection{5.0}; - double lane_changing_lateral_jerk{0.5}; - double minimum_lane_changing_velocity{5.6}; - double lane_change_prepare_duration{4.0}; - LateralAccelerationMap lane_change_lat_acc_map; - - // parked vehicle - double object_check_min_road_shoulder_width{0.5}; - double object_shiftable_ratio_threshold{0.6}; - - // turn signal - double min_length_for_turn_signal_activation{10.0}; - double length_ratio_for_turn_signal_deactivation{0.8}; - - // acceleration data - double min_longitudinal_acc{-1.0}; - double max_longitudinal_acc{1.0}; - - double skip_process_lon_diff_th_prepare{0.5}; - double skip_process_lon_diff_th_lane_changing{1.0}; - - // collision check - bool enable_collision_check_for_prepare_phase_in_general_lanes{false}; - bool enable_collision_check_for_prepare_phase_in_intersection{true}; - bool enable_collision_check_for_prepare_phase_in_turns{true}; - double stopped_object_velocity_threshold{0.1}; - bool check_objects_on_current_lanes{true}; - bool check_objects_on_other_lanes{true}; - bool use_all_predicted_path{false}; - double lane_expansion_left_offset{0.0}; - double lane_expansion_right_offset{0.0}; - - // regulatory elements - bool regulate_on_crosswalk{false}; - bool regulate_on_intersection{false}; - bool regulate_on_traffic_light{false}; - - // ego vehicle stuck detection - double stop_velocity_threshold{0.1}; - double stop_time_threshold{3.0}; - - // true by default for all objects - utils::path_safety_checker::ObjectTypesToCheck object_types_to_check; - - // safety check - bool allow_loose_check_for_cancel{true}; - bool enable_target_lane_bound_check{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}; -}; - enum class States { Normal = 0, Cancel, diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp new file mode 100644 index 0000000000000..d688782ed8d8d --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp @@ -0,0 +1,169 @@ +// 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__PARAMETERS_HPP_ +#define AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PARAMETERS_HPP_ + +#include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" + +#include +#include + +#include +#include + +namespace autoware::behavior_path_planner::lane_change +{ +using utils::path_safety_checker::ObjectTypesToCheck; +using utils::path_safety_checker::RSSparams; + +struct LateralAccelerationMap +{ + std::vector base_vel; + std::vector base_min_acc; + std::vector base_max_acc; + + void add(const double velocity, const double min_acc, const double max_acc) + { + if (base_vel.size() != base_min_acc.size() || base_vel.size() != base_max_acc.size()) { + return; + } + + size_t idx = 0; + for (size_t i = 0; i < base_vel.size(); ++i) { + if (velocity < base_vel.at(i)) { + break; + } + idx = i + 1; + } + + base_vel.insert(base_vel.begin() + idx, velocity); + base_min_acc.insert(base_min_acc.begin() + idx, min_acc); + base_max_acc.insert(base_max_acc.begin() + idx, max_acc); + } + + std::pair find(const double velocity) const + { + if (!base_vel.empty() && velocity < base_vel.front()) { + return std::make_pair(base_min_acc.front(), base_max_acc.front()); + } + if (!base_vel.empty() && velocity > base_vel.back()) { + return std::make_pair(base_min_acc.back(), base_max_acc.back()); + } + + const double min_acc = autoware::interpolation::lerp(base_vel, base_min_acc, velocity); + const double max_acc = autoware::interpolation::lerp(base_vel, base_max_acc, velocity); + + return std::make_pair(min_acc, max_acc); + } +}; + +struct CancelParameters +{ + bool enable_on_prepare_phase{true}; + bool enable_on_lane_changing_phase{false}; + double delta_time{1.0}; + double duration{5.0}; + double max_lateral_jerk{10.0}; + double overhang_tolerance{0.0}; + + // th_unsafe_hysteresis will be compare with the number of detected unsafe instance. If the + // number of unsafe exceeds th_unsafe_hysteresis, the lane change will be cancelled or + // aborted. + int th_unsafe_hysteresis{2}; + + int deceleration_sampling_num{5}; +}; + +struct CollisionCheckParameters +{ + bool enable_for_prepare_phase_in_general_lanes{false}; + bool enable_for_prepare_phase_in_intersection{true}; + bool enable_for_prepare_phase_in_turns{true}; + bool check_current_lane{true}; + bool check_other_lanes{true}; + bool use_all_predicted_paths{false}; + double th_yaw_diff{3.1416}; + double prediction_time_resolution{0.5}; +}; + +struct SafetyParameters +{ + bool enable_loose_check_for_cancel{true}; + bool enable_target_lane_bound_check{true}; + double th_stopped_object_velocity{0.1}; + double lane_expansion_left_offset{0.0}; + double lane_expansion_right_offset{0.0}; + RSSparams rss_params{}; + RSSparams rss_params_for_parked{}; + RSSparams rss_params_for_abort{}; + RSSparams rss_params_for_stuck{}; + ObjectTypesToCheck target_object_types{}; + CollisionCheckParameters collision_check{}; +}; + +struct TrajectoryParameters +{ + double prepare_duration{4.0}; + double lateral_jerk{0.5}; + double min_longitudinal_acc{-1.0}; + double max_longitudinal_acc{1.0}; + double th_prepare_length_diff{0.5}; + double th_lane_changing_length_diff{0.5}; + double min_lane_changing_velocity{5.6}; + int lon_acc_sampling_num{10}; + int lat_acc_sampling_num{10}; + LateralAccelerationMap lat_acc_map{}; +}; + +struct Parameters +{ + TrajectoryParameters trajectory{}; + SafetyParameters safety{}; + CancelParameters cancel{}; + + // lane change parameters + double backward_lane_length{200.0}; + double backward_length_buffer_for_end_of_lane{0.0}; + double backward_length_buffer_for_blocking_object{0.0}; + double backward_length_from_intersection{5.0}; + + // parked vehicle + double object_check_min_road_shoulder_width{0.5}; + double th_object_shiftable_ratio{0.6}; + + // turn signal + double min_length_for_turn_signal_activation{10.0}; + + // regulatory elements + bool regulate_on_crosswalk{false}; + bool regulate_on_intersection{false}; + bool regulate_on_traffic_light{false}; + + // ego vehicle stuck detection + double th_stop_velocity{0.1}; + double th_stop_time{3.0}; + + // finish judge parameter + double lane_change_finish_judge_buffer{3.0}; + double th_finish_judge_lateral_diff{0.2}; + double th_finish_judge_yaw_diff{autoware::universe_utils::deg2rad(3.0)}; + + // debug marker + bool publish_debug_marker{false}; +}; + +} // namespace autoware::behavior_path_planner::lane_change + +#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__PARAMETERS_HPP_ 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 10dba38645f39..2624d0f1a87c6 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 @@ -43,49 +43,72 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s const auto parameter = [](std::string && name) { return "lane_change." + name; }; // trajectory generation - p.backward_lane_length = getOrDeclareParameter(*node, parameter("backward_lane_length")); - p.prediction_time_resolution = - getOrDeclareParameter(*node, parameter("prediction_time_resolution")); - p.longitudinal_acc_sampling_num = - getOrDeclareParameter(*node, parameter("longitudinal_acceleration_sampling_num")); - p.lateral_acc_sampling_num = - getOrDeclareParameter(*node, parameter("lateral_acceleration_sampling_num")); + { + p.trajectory.prepare_duration = + getOrDeclareParameter(*node, parameter("trajectory.prepare_duration")); + p.trajectory.lateral_jerk = + getOrDeclareParameter(*node, parameter("trajectory.lateral_jerk")); + p.trajectory.min_longitudinal_acc = + getOrDeclareParameter(*node, parameter("trajectory.min_longitudinal_acc")); + p.trajectory.max_longitudinal_acc = + getOrDeclareParameter(*node, parameter("trajectory.max_longitudinal_acc")); + p.trajectory.th_prepare_length_diff = + getOrDeclareParameter(*node, parameter("trajectory.th_prepare_length_diff")); + p.trajectory.th_lane_changing_length_diff = + getOrDeclareParameter(*node, parameter("trajectory.th_lane_changing_length_diff")); + p.trajectory.min_lane_changing_velocity = + getOrDeclareParameter(*node, parameter("trajectory.min_lane_changing_velocity")); + p.trajectory.lon_acc_sampling_num = + getOrDeclareParameter(*node, parameter("trajectory.lon_acc_sampling_num")); + p.trajectory.lat_acc_sampling_num = + getOrDeclareParameter(*node, parameter("trajectory.lat_acc_sampling_num")); + + const auto max_acc = getOrDeclareParameter(*node, "normal.max_acc"); + p.trajectory.min_lane_changing_velocity = + std::min(p.trajectory.min_lane_changing_velocity, max_acc * p.trajectory.prepare_duration); + + // validation of trajectory parameters + if (p.trajectory.lon_acc_sampling_num < 1 || p.trajectory.lat_acc_sampling_num < 1) { + RCLCPP_FATAL_STREAM( + node->get_logger().get_child(node_name), + "lane_change_sampling_num must be positive integer. Given longitudinal parameter: " + << p.trajectory.lon_acc_sampling_num + << "Given lateral parameter: " << p.trajectory.lat_acc_sampling_num << std::endl + << "Terminating the program..."); + exit(EXIT_FAILURE); + } + + // lateral acceleration map + const auto lateral_acc_velocity = + getOrDeclareParameter>(*node, parameter("lateral_acceleration.velocity")); + const auto min_lateral_acc = getOrDeclareParameter>( + *node, parameter("lateral_acceleration.min_values")); + const auto max_lateral_acc = getOrDeclareParameter>( + *node, parameter("lateral_acceleration.max_values")); + if ( + lateral_acc_velocity.size() != min_lateral_acc.size() || + lateral_acc_velocity.size() != max_lateral_acc.size()) { + RCLCPP_ERROR( + node->get_logger().get_child(node_name), + "Lane change lateral acceleration map has invalid size."); + exit(EXIT_FAILURE); + } + for (size_t i = 0; i < lateral_acc_velocity.size(); ++i) { + p.trajectory.lat_acc_map.add( + lateral_acc_velocity.at(i), min_lateral_acc.at(i), max_lateral_acc.at(i)); + } + } // parked vehicle detection p.object_check_min_road_shoulder_width = getOrDeclareParameter(*node, parameter("object_check_min_road_shoulder_width")); - p.object_shiftable_ratio_threshold = + p.th_object_shiftable_ratio = getOrDeclareParameter(*node, parameter("object_shiftable_ratio_threshold")); // turn signal p.min_length_for_turn_signal_activation = getOrDeclareParameter(*node, parameter("min_length_for_turn_signal_activation")); - p.length_ratio_for_turn_signal_deactivation = - getOrDeclareParameter(*node, parameter("length_ratio_for_turn_signal_deactivation")); - - // acceleration - p.min_longitudinal_acc = getOrDeclareParameter(*node, parameter("min_longitudinal_acc")); - p.max_longitudinal_acc = getOrDeclareParameter(*node, parameter("max_longitudinal_acc")); - - // collision check - p.enable_collision_check_for_prepare_phase_in_general_lanes = getOrDeclareParameter( - *node, parameter("enable_collision_check_for_prepare_phase.general_lanes")); - p.enable_collision_check_for_prepare_phase_in_intersection = getOrDeclareParameter( - *node, parameter("enable_collision_check_for_prepare_phase.intersection")); - p.enable_collision_check_for_prepare_phase_in_turns = - getOrDeclareParameter(*node, parameter("enable_collision_check_for_prepare_phase.turns")); - p.stopped_object_velocity_threshold = - getOrDeclareParameter(*node, parameter("stopped_object_velocity_threshold")); - p.check_objects_on_current_lanes = - getOrDeclareParameter(*node, parameter("check_objects_on_current_lanes")); - p.check_objects_on_other_lanes = - getOrDeclareParameter(*node, parameter("check_objects_on_other_lanes")); - p.use_all_predicted_path = - getOrDeclareParameter(*node, parameter("use_all_predicted_path")); - p.lane_expansion_left_offset = - getOrDeclareParameter(*node, parameter("safety_check.lane_expansion.left_offset")); - p.lane_expansion_right_offset = - getOrDeclareParameter(*node, parameter("safety_check.lane_expansion.right_offset")); + // lane change regulations p.regulate_on_crosswalk = getOrDeclareParameter(*node, parameter("regulation.crosswalk")); p.regulate_on_intersection = @@ -94,99 +117,85 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("regulation.traffic_light")); // ego vehicle stuck detection - p.stop_velocity_threshold = - getOrDeclareParameter(*node, parameter("stuck_detection.velocity")); - p.stop_time_threshold = - getOrDeclareParameter(*node, parameter("stuck_detection.stop_time")); - - // safety check - p.allow_loose_check_for_cancel = - getOrDeclareParameter(*node, parameter("safety_check.allow_loose_check_for_cancel")); - p.enable_target_lane_bound_check = - getOrDeclareParameter(*node, parameter("safety_check.enable_target_lane_bound_check")); - p.collision_check_yaw_diff_threshold = getOrDeclareParameter( - *node, parameter("safety_check.collision_check_yaw_diff_threshold")); - - p.rss_params.longitudinal_distance_min_threshold = getOrDeclareParameter( - *node, parameter("safety_check.execution.longitudinal_distance_min_threshold")); - p.rss_params.longitudinal_distance_min_threshold = getOrDeclareParameter( - *node, parameter("safety_check.execution.longitudinal_distance_min_threshold")); - p.rss_params.longitudinal_velocity_delta_time = getOrDeclareParameter( - *node, parameter("safety_check.execution.longitudinal_velocity_delta_time")); - p.rss_params.front_vehicle_deceleration = getOrDeclareParameter( - *node, parameter("safety_check.execution.expected_front_deceleration")); - p.rss_params.rear_vehicle_deceleration = getOrDeclareParameter( - *node, parameter("safety_check.execution.expected_rear_deceleration")); - p.rss_params.rear_vehicle_reaction_time = getOrDeclareParameter( - *node, parameter("safety_check.execution.rear_vehicle_reaction_time")); - p.rss_params.rear_vehicle_safety_time_margin = getOrDeclareParameter( - *node, parameter("safety_check.execution.rear_vehicle_safety_time_margin")); - 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( - *node, parameter("safety_check.cancel.longitudinal_velocity_delta_time")); - p.rss_params_for_abort.front_vehicle_deceleration = getOrDeclareParameter( - *node, parameter("safety_check.cancel.expected_front_deceleration")); - p.rss_params_for_abort.rear_vehicle_deceleration = getOrDeclareParameter( - *node, parameter("safety_check.cancel.expected_rear_deceleration")); - p.rss_params_for_abort.rear_vehicle_reaction_time = getOrDeclareParameter( - *node, parameter("safety_check.cancel.rear_vehicle_reaction_time")); - p.rss_params_for_abort.rear_vehicle_safety_time_margin = getOrDeclareParameter( - *node, parameter("safety_check.cancel.rear_vehicle_safety_time_margin")); - p.rss_params_for_abort.lateral_distance_max_threshold = getOrDeclareParameter( - *node, parameter("safety_check.cancel.lateral_distance_max_threshold")); - - p.rss_params_for_stuck.longitudinal_distance_min_threshold = getOrDeclareParameter( - *node, parameter("safety_check.stuck.longitudinal_distance_min_threshold")); - p.rss_params_for_stuck.longitudinal_velocity_delta_time = getOrDeclareParameter( - *node, parameter("safety_check.stuck.longitudinal_velocity_delta_time")); - p.rss_params_for_stuck.front_vehicle_deceleration = getOrDeclareParameter( - *node, parameter("safety_check.stuck.expected_front_deceleration")); - p.rss_params_for_stuck.rear_vehicle_deceleration = getOrDeclareParameter( - *node, parameter("safety_check.stuck.expected_rear_deceleration")); - p.rss_params_for_stuck.rear_vehicle_reaction_time = getOrDeclareParameter( - *node, parameter("safety_check.stuck.rear_vehicle_reaction_time")); - p.rss_params_for_stuck.rear_vehicle_safety_time_margin = getOrDeclareParameter( - *node, parameter("safety_check.stuck.rear_vehicle_safety_time_margin")); - p.rss_params_for_stuck.lateral_distance_max_threshold = getOrDeclareParameter( - *node, parameter("safety_check.stuck.lateral_distance_max_threshold")); + p.th_stop_velocity = getOrDeclareParameter(*node, parameter("stuck_detection.velocity")); + p.th_stop_time = getOrDeclareParameter(*node, parameter("stuck_detection.stop_time")); + + // safety + { + p.safety.enable_loose_check_for_cancel = + getOrDeclareParameter(*node, parameter("safety_check.allow_loose_check_for_cancel")); + p.safety.enable_target_lane_bound_check = + getOrDeclareParameter(*node, parameter("safety_check.enable_target_lane_bound_check")); + p.safety.th_stopped_object_velocity = getOrDeclareParameter( + *node, parameter("safety_check.stopped_object_velocity_threshold")); + p.safety.lane_expansion_left_offset = + getOrDeclareParameter(*node, parameter("safety_check.lane_expansion.left_offset")); + p.safety.lane_expansion_right_offset = + getOrDeclareParameter(*node, parameter("safety_check.lane_expansion.right_offset")); + + // collision check + p.safety.collision_check.enable_for_prepare_phase_in_general_lanes = + getOrDeclareParameter( + *node, parameter("collision_check.enable_for_prepare_phase.general_lanes")); + p.safety.collision_check.enable_for_prepare_phase_in_intersection = getOrDeclareParameter( + *node, parameter("collision_check.enable_for_prepare_phase.intersection")); + p.safety.collision_check.enable_for_prepare_phase_in_turns = getOrDeclareParameter( + *node, parameter("collision_check.enable_for_prepare_phase.turns")); + p.safety.collision_check.check_current_lane = + getOrDeclareParameter(*node, parameter("collision_check.check_current_lanes")); + p.safety.collision_check.check_other_lanes = + getOrDeclareParameter(*node, parameter("collision_check.check_other_lanes")); + p.safety.collision_check.use_all_predicted_paths = + getOrDeclareParameter(*node, parameter("collision_check.use_all_predicted_paths")); + p.safety.collision_check.prediction_time_resolution = + getOrDeclareParameter(*node, parameter("collision_check.prediction_time_resolution")); + p.safety.collision_check.th_yaw_diff = + getOrDeclareParameter(*node, parameter("collision_check.yaw_diff_threshold")); + + // rss check + auto set_rss_params = [&](auto & params, const std::string & prefix) { + params.longitudinal_distance_min_threshold = getOrDeclareParameter( + *node, parameter(prefix + ".longitudinal_distance_min_threshold")); + params.longitudinal_velocity_delta_time = getOrDeclareParameter( + *node, parameter(prefix + ".longitudinal_velocity_delta_time")); + params.front_vehicle_deceleration = + getOrDeclareParameter(*node, parameter(prefix + ".expected_front_deceleration")); + params.rear_vehicle_deceleration = + getOrDeclareParameter(*node, parameter(prefix + ".expected_rear_deceleration")); + params.rear_vehicle_reaction_time = + getOrDeclareParameter(*node, parameter(prefix + ".rear_vehicle_reaction_time")); + params.rear_vehicle_safety_time_margin = getOrDeclareParameter( + *node, parameter(prefix + ".rear_vehicle_safety_time_margin")); + params.lateral_distance_max_threshold = + getOrDeclareParameter(*node, parameter(prefix + ".lateral_distance_max_threshold")); + }; + set_rss_params(p.safety.rss_params, "safety_check.execution"); + set_rss_params(p.safety.rss_params_for_parked, "safety_check.parked"); + set_rss_params(p.safety.rss_params_for_abort, "safety_check.cancel"); + set_rss_params(p.safety.rss_params_for_stuck, "safety_check.stuck"); + + // target object types + const std::string ns = "lane_change.target_object."; + p.safety.target_object_types.check_car = getOrDeclareParameter(*node, ns + "car"); + p.safety.target_object_types.check_truck = getOrDeclareParameter(*node, ns + "truck"); + p.safety.target_object_types.check_bus = getOrDeclareParameter(*node, ns + "bus"); + p.safety.target_object_types.check_trailer = getOrDeclareParameter(*node, ns + "trailer"); + p.safety.target_object_types.check_unknown = getOrDeclareParameter(*node, ns + "unknown"); + p.safety.target_object_types.check_bicycle = getOrDeclareParameter(*node, ns + "bicycle"); + p.safety.target_object_types.check_motorcycle = + getOrDeclareParameter(*node, ns + "motorcycle"); + p.safety.target_object_types.check_pedestrian = + getOrDeclareParameter(*node, ns + "pedestrian"); + } // lane change parameters - const auto max_acc = getOrDeclareParameter(*node, "normal.max_acc"); + p.backward_lane_length = getOrDeclareParameter(*node, parameter("backward_lane_length")); p.backward_length_buffer_for_end_of_lane = getOrDeclareParameter(*node, parameter("backward_length_buffer_for_end_of_lane")); p.backward_length_buffer_for_blocking_object = getOrDeclareParameter(*node, parameter("backward_length_buffer_for_blocking_object")); p.backward_length_from_intersection = getOrDeclareParameter(*node, parameter("backward_length_from_intersection")); - p.lane_changing_lateral_jerk = - getOrDeclareParameter(*node, parameter("lane_changing_lateral_jerk")); - p.lane_change_prepare_duration = - getOrDeclareParameter(*node, parameter("prepare_duration")); - p.minimum_lane_changing_velocity = - 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); if (p.backward_length_buffer_for_end_of_lane < 1.0) { RCLCPP_WARN_STREAM( @@ -194,41 +203,6 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s "Lane change buffer must be more than 1 meter. Modifying the buffer."); } - // lateral acceleration map for lane change - const auto lateral_acc_velocity = - getOrDeclareParameter>(*node, parameter("lateral_acceleration.velocity")); - const auto min_lateral_acc = - getOrDeclareParameter>(*node, parameter("lateral_acceleration.min_values")); - const auto max_lateral_acc = - getOrDeclareParameter>(*node, parameter("lateral_acceleration.max_values")); - if ( - lateral_acc_velocity.size() != min_lateral_acc.size() || - lateral_acc_velocity.size() != max_lateral_acc.size()) { - RCLCPP_ERROR( - node->get_logger().get_child(node_name), - "Lane change lateral acceleration map has invalid size."); - exit(EXIT_FAILURE); - } - for (size_t i = 0; i < lateral_acc_velocity.size(); ++i) { - p.lane_change_lat_acc_map.add( - lateral_acc_velocity.at(i), min_lateral_acc.at(i), max_lateral_acc.at(i)); - } - - // target object - { - const std::string ns = "lane_change.target_object."; - p.object_types_to_check.check_car = getOrDeclareParameter(*node, ns + "car"); - p.object_types_to_check.check_truck = getOrDeclareParameter(*node, ns + "truck"); - p.object_types_to_check.check_bus = getOrDeclareParameter(*node, ns + "bus"); - p.object_types_to_check.check_trailer = getOrDeclareParameter(*node, ns + "trailer"); - p.object_types_to_check.check_unknown = getOrDeclareParameter(*node, ns + "unknown"); - p.object_types_to_check.check_bicycle = getOrDeclareParameter(*node, ns + "bicycle"); - p.object_types_to_check.check_motorcycle = - getOrDeclareParameter(*node, ns + "motorcycle"); - p.object_types_to_check.check_pedestrian = - getOrDeclareParameter(*node, ns + "pedestrian"); - } - // lane change cancel p.cancel.enable_on_prepare_phase = getOrDeclareParameter(*node, parameter("cancel.enable_on_prepare_phase")); @@ -240,7 +214,7 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("cancel.max_lateral_jerk")); p.cancel.overhang_tolerance = getOrDeclareParameter(*node, parameter("cancel.overhang_tolerance")); - p.cancel.unsafe_hysteresis_threshold = + p.cancel.th_unsafe_hysteresis = getOrDeclareParameter(*node, parameter("cancel.unsafe_hysteresis_threshold")); p.cancel.deceleration_sampling_num = getOrDeclareParameter(*node, parameter("cancel.deceleration_sampling_num")); @@ -248,43 +222,35 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s // finish judge parameters p.lane_change_finish_judge_buffer = getOrDeclareParameter(*node, parameter("lane_change_finish_judge_buffer")); - p.finish_judge_lateral_threshold = + p.th_finish_judge_lateral_diff = 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 = + p.th_finish_judge_yaw_diff = autoware::universe_utils::deg2rad(finish_judge_lateral_angle_deviation); // debug marker p.publish_debug_marker = getOrDeclareParameter(*node, parameter("publish_debug_marker")); - // validation of parameters - if (p.longitudinal_acc_sampling_num < 1 || p.lateral_acc_sampling_num < 1) { - RCLCPP_FATAL_STREAM( - node->get_logger().get_child(node_name), - "lane_change_sampling_num must be positive integer. Given longitudinal parameter: " - << p.longitudinal_acc_sampling_num - << "Given lateral parameter: " << p.lateral_acc_sampling_num << std::endl - << "Terminating the program..."); - exit(EXIT_FAILURE); - } - // validation of safety check parameters - // if loosely check is not allowed, lane change module will keep on chattering and canceling, and + // if loose check is not enabled, lane change module will keep on chattering and canceling, and // false positive situation might occur - if (!p.allow_loose_check_for_cancel) { + if (!p.safety.enable_loose_check_for_cancel) { if ( - p.rss_params.front_vehicle_deceleration > p.rss_params_for_abort.front_vehicle_deceleration || - p.rss_params.rear_vehicle_deceleration > p.rss_params_for_abort.rear_vehicle_deceleration || - p.rss_params.rear_vehicle_reaction_time > p.rss_params_for_abort.rear_vehicle_reaction_time || - p.rss_params.rear_vehicle_safety_time_margin > - p.rss_params_for_abort.rear_vehicle_safety_time_margin || - p.rss_params.lateral_distance_max_threshold > - p.rss_params_for_abort.lateral_distance_max_threshold || - p.rss_params.longitudinal_distance_min_threshold > - p.rss_params_for_abort.longitudinal_distance_min_threshold || - p.rss_params.longitudinal_velocity_delta_time > - p.rss_params_for_abort.longitudinal_velocity_delta_time) { + p.safety.rss_params.front_vehicle_deceleration > + p.safety.rss_params_for_abort.front_vehicle_deceleration || + p.safety.rss_params.rear_vehicle_deceleration > + p.safety.rss_params_for_abort.rear_vehicle_deceleration || + p.safety.rss_params.rear_vehicle_reaction_time > + p.safety.rss_params_for_abort.rear_vehicle_reaction_time || + p.safety.rss_params.rear_vehicle_safety_time_margin > + p.safety.rss_params_for_abort.rear_vehicle_safety_time_margin || + p.safety.rss_params.lateral_distance_max_threshold > + p.safety.rss_params_for_abort.lateral_distance_max_threshold || + p.safety.rss_params.longitudinal_distance_min_threshold > + p.safety.rss_params_for_abort.longitudinal_distance_min_threshold || + p.safety.rss_params.longitudinal_velocity_delta_time > + p.safety.rss_params_for_abort.longitudinal_velocity_delta_time) { RCLCPP_FATAL_STREAM( node->get_logger().get_child(node_name), "abort parameter might be loose... Terminating the program..."); @@ -323,8 +289,6 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "backward_lane_length", p->backward_lane_length); - updateParam(parameters, ns + "prepare_duration", p->lane_change_prepare_duration); - updateParam( parameters, ns + "backward_length_buffer_for_end_of_lane", p->backward_length_buffer_for_end_of_lane); @@ -335,59 +299,57 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectorlane_change_finish_judge_buffer); updateParam( - parameters, ns + "lane_changing_lateral_jerk", p->lane_changing_lateral_jerk); + parameters, ns + "finish_judge_lateral_threshold", p->th_finish_judge_lateral_diff); + updateParam(parameters, ns + "publish_debug_marker", p->publish_debug_marker); + } + { + const std::string ns = "lane_change.trajectory."; + updateParam(parameters, ns + "prepare_duration", p->trajectory.prepare_duration); + updateParam(parameters, ns + "lateral_jerk", p->trajectory.lateral_jerk); updateParam( - parameters, ns + "minimum_lane_changing_velocity", p->minimum_lane_changing_velocity); + parameters, ns + ".min_lane_changing_velocity", p->trajectory.min_lane_changing_velocity); + // longitudinal acceleration updateParam( - parameters, ns + "prediction_time_resolution", p->prediction_time_resolution); - + parameters, ns + "min_longitudinal_acc", p->trajectory.min_longitudinal_acc); + updateParam( + parameters, ns + "max_longitudinal_acc", p->trajectory.max_longitudinal_acc); int longitudinal_acc_sampling_num = 0; - updateParam( - parameters, ns + "longitudinal_acceleration_sampling_num", longitudinal_acc_sampling_num); + updateParam(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { - p->longitudinal_acc_sampling_num = longitudinal_acc_sampling_num; + p->trajectory.lon_acc_sampling_num = longitudinal_acc_sampling_num; } int lateral_acc_sampling_num = 0; - updateParam( - parameters, ns + "lateral_acceleration_sampling_num", lateral_acc_sampling_num); + updateParam(parameters, ns + "lat_acc_sampling_num", lateral_acc_sampling_num); if (lateral_acc_sampling_num > 0) { - p->lateral_acc_sampling_num = lateral_acc_sampling_num; + p->trajectory.lat_acc_sampling_num = lateral_acc_sampling_num; } updateParam( - parameters, ns + "finish_judge_lateral_threshold", p->finish_judge_lateral_threshold); - updateParam(parameters, ns + "publish_debug_marker", p->publish_debug_marker); - - // longitudinal acceleration - updateParam(parameters, ns + "min_longitudinal_acc", p->min_longitudinal_acc); - updateParam(parameters, ns + "max_longitudinal_acc", p->max_longitudinal_acc); - } - - { - const std::string ns = "lane_change.skip_process.longitudinal_distance_diff_threshold."; - updateParam(parameters, ns + "prepare", p->skip_process_lon_diff_th_prepare); + parameters, ns + "th_prepare_length_diff", p->trajectory.th_prepare_length_diff); updateParam( - parameters, ns + "lane_changing", p->skip_process_lon_diff_th_lane_changing); + parameters, ns + "th_lane_changing_length_diff", p->trajectory.th_lane_changing_length_diff); } { const std::string ns = "lane_change.safety_check.lane_expansion."; - updateParam(parameters, ns + "left_offset", p->lane_expansion_left_offset); - updateParam(parameters, ns + "right_offset", p->lane_expansion_right_offset); + updateParam(parameters, ns + "left_offset", p->safety.lane_expansion_left_offset); + updateParam(parameters, ns + "right_offset", p->safety.lane_expansion_right_offset); } { const std::string ns = "lane_change.target_object."; - updateParam(parameters, ns + "car", p->object_types_to_check.check_car); - updateParam(parameters, ns + "truck", p->object_types_to_check.check_truck); - updateParam(parameters, ns + "bus", p->object_types_to_check.check_bus); - updateParam(parameters, ns + "trailer", p->object_types_to_check.check_trailer); - updateParam(parameters, ns + "unknown", p->object_types_to_check.check_unknown); - updateParam(parameters, ns + "bicycle", p->object_types_to_check.check_bicycle); - updateParam(parameters, ns + "motorcycle", p->object_types_to_check.check_motorcycle); - updateParam(parameters, ns + "pedestrian", p->object_types_to_check.check_pedestrian); + updateParam(parameters, ns + "car", p->safety.target_object_types.check_car); + updateParam(parameters, ns + "truck", p->safety.target_object_types.check_truck); + updateParam(parameters, ns + "bus", p->safety.target_object_types.check_bus); + updateParam(parameters, ns + "trailer", p->safety.target_object_types.check_trailer); + updateParam(parameters, ns + "unknown", p->safety.target_object_types.check_unknown); + updateParam(parameters, ns + "bicycle", p->safety.target_object_types.check_bicycle); + updateParam( + parameters, ns + "motorcycle", p->safety.target_object_types.check_motorcycle); + updateParam( + parameters, ns + "pedestrian", p->safety.target_object_types.check_pedestrian); } { @@ -399,8 +361,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "velocity", p->stop_velocity_threshold); - updateParam(parameters, ns + "stop_time", p->stop_time_threshold); + updateParam(parameters, ns + "velocity", p->th_stop_velocity); + updateParam(parameters, ns + "stop_time", p->th_stop_time); } { @@ -425,7 +387,7 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "max_lateral_jerk", p->cancel.max_lateral_jerk); updateParam(parameters, ns + "overhang_tolerance", p->cancel.overhang_tolerance); updateParam( - parameters, ns + "unsafe_hysteresis_threshold", p->cancel.unsafe_hysteresis_threshold); + parameters, ns + "unsafe_hysteresis_threshold", p->cancel.th_unsafe_hysteresis); } std::for_each(observers_.begin(), observers_.end(), [&p](const auto & observer) { if (!observer.expired()) observer.lock()->updateModuleParams(p); 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 942902b836c95..2e9b9e337e51c 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 @@ -289,7 +289,7 @@ bool NormalLaneChange::is_near_regulatory_element() const if (common_data_ptr_->transient_data.is_ego_near_current_terminal_start) return false; - const bool only_tl = getStopTime() >= lane_change_parameters_->stop_time_threshold; + const bool only_tl = getStopTime() >= lane_change_parameters_->th_stop_time; if (only_tl) { RCLCPP_DEBUG(logger_, "Stop time is over threshold. Ignore crosswalk and intersection checks."); @@ -556,7 +556,8 @@ void NormalLaneChange::insert_stop_point_on_current_lanes(PathWithLaneId & path) // margin with leading vehicle // consider rss distance when the LC need to avoid obstacles const auto rss_dist = calcRssDistance( - 0.0, lc_param_ptr->minimum_lane_changing_velocity, lc_param_ptr->rss_params_for_parked); + 0.0, lc_param_ptr->trajectory.min_lane_changing_velocity, + lc_param_ptr->safety.rss_params_for_parked); const auto stop_margin = transient_data.lane_changing_length.min + lc_param_ptr->backward_length_buffer_for_blocking_object + rss_dist + @@ -753,13 +754,13 @@ bool NormalLaneChange::hasFinishedLaneChange() const 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) { + if (yaw_deviation_to_centerline > lane_change_parameters_->th_finish_judge_yaw_diff) { return false; } const auto & arc_length = common_data_ptr_->transient_data.target_lanes_ego_arc; const auto reach_target_lane = - std::abs(arc_length.distance) < lane_change_parameters_->finish_judge_lateral_threshold; + std::abs(arc_length.distance) < lane_change_parameters_->th_finish_judge_lateral_diff; lane_change_debug_.distance_to_lane_change_finished = arc_length.distance; @@ -791,7 +792,7 @@ bool NormalLaneChange::isAbleToReturnCurrentLane() const planner_data_->parameters.ego_nearest_yaw_threshold); const double ego_velocity = - std::max(getEgoVelocity(), lane_change_parameters_->minimum_lane_changing_velocity); + std::max(getEgoVelocity(), lane_change_parameters_->trajectory.min_lane_changing_velocity); const double estimated_travel_dist = ego_velocity * lane_change_parameters_->cancel.delta_time; double dist = 0.0; @@ -952,12 +953,14 @@ lane_change::TargetObjects NormalLaneChange::get_target_objects( insert_leading_objects(filtered_objects.target_lane_leading.stopped); insert_leading_objects(filtered_objects.target_lane_leading.stopped_at_bound); - const auto chk_obj_in_curr_lanes = lane_change_parameters_->check_objects_on_current_lanes; + const auto chk_obj_in_curr_lanes = + lane_change_parameters_->safety.collision_check.check_current_lane; if (chk_obj_in_curr_lanes || common_data_ptr_->transient_data.is_ego_stuck) { insert_leading_objects(filtered_objects.current_lane); } - const auto chk_obj_in_other_lanes = lane_change_parameters_->check_objects_on_other_lanes; + const auto chk_obj_in_other_lanes = + lane_change_parameters_->safety.collision_check.check_other_lanes; if (chk_obj_in_other_lanes) { insert_leading_objects(filtered_objects.others); } @@ -969,7 +972,7 @@ FilteredLanesObjects NormalLaneChange::filter_objects() const { auto objects = *planner_data_->dynamic_object; utils::path_safety_checker::filterObjectsByClass( - objects, lane_change_parameters_->object_types_to_check); + objects, lane_change_parameters_->safety.target_object_types); if (objects.objects.empty()) { return {}; @@ -1004,10 +1007,10 @@ FilteredLanesObjects NormalLaneChange::filter_objects() const filtered_objects.target_lane_trailing.reserve(reserve_size); filtered_objects.others.reserve(reserve_size); - const auto stopped_obj_vel_th = common_data_ptr_->lc_param_ptr->stopped_object_velocity_threshold; + const auto stopped_obj_vel_th = lane_change_parameters_->safety.th_stopped_object_velocity; for (const auto & object : objects.objects) { - auto ext_object = utils::lane_change::transform(object, *common_data_ptr_->lc_param_ptr); + auto ext_object = utils::lane_change::transform(object, *lane_change_parameters_); const auto & ext_obj_pose = ext_object.initial_pose; ext_object.dist_from_ego = autoware::motion_utils::calcSignedArcLength( current_lanes_ref_path.points, current_pose.position, ext_obj_pose.position); @@ -1186,9 +1189,9 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) const auto prepare_phase_metrics = get_prepare_metrics(); candidate_paths.reserve( - prepare_phase_metrics.size() * lane_change_parameters_->lateral_acc_sampling_num); + prepare_phase_metrics.size() * lane_change_parameters_->trajectory.lat_acc_sampling_num); - const bool only_tl = getStopTime() >= lane_change_parameters_->stop_time_threshold; + const bool only_tl = getStopTime() >= lane_change_parameters_->th_stop_time; const auto dist_to_next_regulatory_element = utils::lane_change::get_distance_to_next_regulatory_element(common_data_ptr_, only_tl, only_tl); @@ -1197,12 +1200,12 @@ bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) if (candidate_paths.empty()) return true; const auto prep_diff = std::abs(candidate_paths.back().info.length.prepare - prep_length); - if (prep_diff > lane_change_parameters_->skip_process_lon_diff_th_prepare) return true; + if (prep_diff > lane_change_parameters_->trajectory.th_prepare_length_diff) return true; if (!check_lc) return false; const auto lc_diff = std::abs(candidate_paths.back().info.length.lane_changing - lc_length); - return lc_diff > lane_change_parameters_->skip_process_lon_diff_th_lane_changing; + return lc_diff > lane_change_parameters_->trajectory.th_lane_changing_length_diff; }; for (const auto & prep_metric : prepare_phase_metrics) { @@ -1346,11 +1349,11 @@ bool NormalLaneChange::check_candidate_path_safety( } const auto lc_start_velocity = candidate_path.info.velocity.prepare; - const auto min_lc_velocity = lane_change_parameters_->minimum_lane_changing_velocity; + const auto min_lc_velocity = lane_change_parameters_->trajectory.min_lane_changing_velocity; constexpr double margin = 0.1; // path is unsafe if it exceeds target lane boundary with a high velocity if ( - lane_change_parameters_->enable_target_lane_bound_check && + lane_change_parameters_->safety.enable_target_lane_bound_check && lc_start_velocity > min_lc_velocity + margin && utils::lane_change::path_footprint_exceeds_target_lane_bound( common_data_ptr_, candidate_path.shifted_path.path, planner_data_->parameters.vehicle_info)) { @@ -1359,12 +1362,12 @@ bool NormalLaneChange::check_candidate_path_safety( constexpr size_t decel_sampling_num = 1; const auto safety_check_with_normal_rss = isLaneChangePathSafe( - candidate_path, target_objects, common_data_ptr_->lc_param_ptr->rss_params, decel_sampling_num, - lane_change_debug_.collision_check_objects); + candidate_path, target_objects, common_data_ptr_->lc_param_ptr->safety.rss_params, + decel_sampling_num, lane_change_debug_.collision_check_objects); if (!safety_check_with_normal_rss.is_safe && is_stuck) { const auto safety_check_with_stuck_rss = isLaneChangePathSafe( - candidate_path, target_objects, common_data_ptr_->lc_param_ptr->rss_params_for_stuck, + candidate_path, target_objects, common_data_ptr_->lc_param_ptr->safety.rss_params_for_stuck, decel_sampling_num, lane_change_debug_.collision_check_objects); return safety_check_with_stuck_rss.is_safe; } @@ -1392,7 +1395,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( const auto & route_handler = *getRouteHandler(); const auto minimum_lane_changing_velocity = - lane_change_parameters_->minimum_lane_changing_velocity; + lane_change_parameters_->trajectory.min_lane_changing_velocity; const auto is_goal_in_route = route_handler.isInGoalRouteSection(target_lanes.back()); @@ -1433,10 +1436,10 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( target_lanes, lane_changing_start_pose.value()); const auto [min_lateral_acc, max_lateral_acc] = - lane_change_parameters_->lane_change_lat_acc_map.find(minimum_lane_changing_velocity); + lane_change_parameters_->trajectory.lat_acc_map.find(minimum_lane_changing_velocity); const auto lane_changing_time = autoware::motion_utils::calc_shift_time_from_jerk( - shift_length, lane_change_parameters_->lane_changing_lateral_jerk, max_lateral_acc); + shift_length, lane_change_parameters_->trajectory.lateral_jerk, max_lateral_acc); const auto target_lane_length = common_data_ptr_->transient_data.target_lane_length; const auto target_segment = getTargetSegment( @@ -1528,7 +1531,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const } const auto safety_status = isLaneChangePathSafe( - path, target_objects, lane_change_parameters_->rss_params_for_abort, + path, target_objects, lane_change_parameters_->safety.rss_params_for_abort, static_cast(lane_change_parameters_->cancel.deceleration_sampling_num), debug_data); { // only for debug purpose @@ -1562,7 +1565,7 @@ PathSafetyStatus NormalLaneChange::evaluateApprovedPathWithUnsafeHysteresis( } unsafe_hysteresis_count_ = 0; } - if (unsafe_hysteresis_count_ > lane_change_parameters_->cancel.unsafe_hysteresis_threshold) { + if (unsafe_hysteresis_count_ > lane_change_parameters_->cancel.th_unsafe_hysteresis) { RCLCPP_DEBUG( logger_, "%s: hysteresis count exceed threshold. lane change is now %s", __func__, (approved_path_safety_status.is_safe ? "safe" : "UNSAFE")); @@ -1624,7 +1627,7 @@ bool NormalLaneChange::calcAbortPath() const auto & route_handler = getRouteHandler(); const auto & common_param = getCommonParam(); const auto current_velocity = - std::max(lane_change_parameters_->minimum_lane_changing_velocity, getEgoVelocity()); + std::max(lane_change_parameters_->trajectory.min_lane_changing_velocity, getEgoVelocity()); const auto current_pose = getEgoPose(); const auto & selected_path = status_.lane_change_path; @@ -1707,7 +1710,7 @@ bool NormalLaneChange::calcAbortPath() shift_line.end_shift_length, abort_start_dist, current_velocity); path_shifter.setVelocity(current_velocity); const auto lateral_acc_range = - lane_change_parameters_->lane_change_lat_acc_map.find(current_velocity); + lane_change_parameters_->trajectory.lat_acc_map.find(current_velocity); const double & max_lateral_acc = lateral_acc_range.second; path_shifter.setLateralAccelerationLimit(max_lateral_acc); @@ -1827,8 +1830,10 @@ bool NormalLaneChange::has_collision_with_decel_patterns( acceleration_values.begin(), acceleration_values.end(), acceleration_values.begin(), [&](double n) { return lane_changing_acc + n * acc_resolution; }); - const auto time_resolution = lane_change_parameters_->prediction_time_resolution; + const auto time_resolution = + lane_change_parameters_->safety.collision_check.prediction_time_resolution; + const auto stopped_obj_vel_th = lane_change_parameters_->safety.th_stopped_object_velocity; const auto all_collided = std::all_of( acceleration_values.begin(), acceleration_values.end(), [&](const auto acceleration) { const auto ego_predicted_path = utils::lane_change::convertToPredictedPath( @@ -1838,10 +1843,9 @@ bool NormalLaneChange::has_collision_with_decel_patterns( utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution); return std::any_of(objects.begin(), objects.end(), [&](const auto & obj) { - const auto selected_rss_param = - (obj.initial_twist.linear.x <= lane_change_parameters_->stopped_object_velocity_threshold) - ? lane_change_parameters_->rss_params_for_parked - : rss_param; + const auto selected_rss_param = (obj.initial_twist.linear.x <= stopped_obj_vel_th) + ? lane_change_parameters_->safety.rss_params_for_parked + : rss_param; return is_collided( lane_change_path, obj, ego_predicted_path, selected_rss_param, check_prepare_phase, debug_data); @@ -1880,11 +1884,11 @@ bool NormalLaneChange::is_collided( constexpr auto collision_check_yaw_diff_threshold{M_PI}; constexpr auto hysteresis_factor{1.0}; const auto obj_predicted_paths = utils::path_safety_checker::getPredictedPathFromObj( - obj, lane_change_parameters_->use_all_predicted_path); + obj, lane_change_parameters_->safety.collision_check.use_all_predicted_paths); const auto safety_check_max_vel = get_max_velocity_for_safety_check(); const auto & bpp_param = *common_data_ptr_->bpp_param_ptr; - const double velocity_threshold = lane_change_parameters_->stopped_object_velocity_threshold; + const double velocity_threshold = lane_change_parameters_->safety.th_stopped_object_velocity; const double prepare_duration = lane_change_path.info.duration.prepare; const double start_time = check_prepare_phase ? 0.0 : prepare_duration; @@ -1946,13 +1950,13 @@ bool NormalLaneChange::is_ego_stuck() const universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto & lc_param_ptr = common_data_ptr_->lc_param_ptr; - if (std::abs(common_data_ptr_->get_ego_speed()) > lc_param_ptr->stop_velocity_threshold) { + if (std::abs(common_data_ptr_->get_ego_speed()) > lc_param_ptr->th_stop_velocity) { RCLCPP_DEBUG(logger_, "Ego is still moving, not in stuck"); return false; } // Ego is just stopped, not sure it is in stuck yet. - if (getStopTime() < lc_param_ptr->stop_time_threshold) { + if (getStopTime() < lc_param_ptr->th_stop_time) { RCLCPP_DEBUG(logger_, "Ego is just stopped, counting for stuck judge... (%f)", getStopTime()); return false; } @@ -1960,8 +1964,8 @@ bool NormalLaneChange::is_ego_stuck() const // Check if any stationary object exist in obstacle_check_distance const auto & current_lanes_path = common_data_ptr_->current_lanes_path; const auto & ego_pose = common_data_ptr_->get_ego_pose(); - const auto rss_dist = - calcRssDistance(0.0, lc_param_ptr->minimum_lane_changing_velocity, lc_param_ptr->rss_params); + const auto rss_dist = calcRssDistance( + 0.0, lc_param_ptr->trajectory.min_lane_changing_velocity, lc_param_ptr->safety.rss_params); // It is difficult to define the detection range. If it is too short, the stuck will not be // determined, even though you are stuck by an obstacle. If it is too long, @@ -1978,7 +1982,7 @@ bool NormalLaneChange::is_ego_stuck() const // Note: it needs chattering prevention. if ( std::abs(object.initial_twist.linear.x) > - lc_param_ptr->stopped_object_velocity_threshold) { // check if stationary + lc_param_ptr->safety.th_stopped_object_velocity) { // check if stationary return false; } @@ -2016,14 +2020,14 @@ void NormalLaneChange::updateStopTime() universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); const auto current_vel = getEgoVelocity(); - if (std::abs(current_vel) > lane_change_parameters_->stop_velocity_threshold) { + if (std::abs(current_vel) > lane_change_parameters_->th_stop_velocity) { stop_time_ = 0.0; } else { const double duration = stop_watch_.toc("stop_time"); // clip stop time - if (stop_time_ + duration * 0.001 > lane_change_parameters_->stop_time_threshold) { + if (stop_time_ + duration * 0.001 > lane_change_parameters_->th_stop_time) { constexpr double eps = 0.1; - stop_time_ = lane_change_parameters_->stop_time_threshold + eps; + stop_time_ = lane_change_parameters_->th_stop_time + eps; } else { stop_time_ += duration * 0.001; } @@ -2037,7 +2041,7 @@ bool NormalLaneChange::check_prepare_phase() const const auto & route_handler = getRouteHandler(); const auto check_in_general_lanes = - lane_change_parameters_->enable_collision_check_for_prepare_phase_in_general_lanes; + lane_change_parameters_->safety.collision_check.enable_for_prepare_phase_in_general_lanes; lanelet::ConstLanelet current_lane; if (!route_handler->getClosestLaneletWithinRoute(getEgoPose(), ¤t_lane)) { @@ -2048,11 +2052,11 @@ bool NormalLaneChange::check_prepare_phase() const } const auto check_in_intersection = - lane_change_parameters_->enable_collision_check_for_prepare_phase_in_intersection && + lane_change_parameters_->safety.collision_check.enable_for_prepare_phase_in_intersection && common_data_ptr_->transient_data.in_intersection; const auto check_in_turns = - lane_change_parameters_->enable_collision_check_for_prepare_phase_in_turns && + lane_change_parameters_->safety.collision_check.enable_for_prepare_phase_in_turns && common_data_ptr_->transient_data.in_turn_direction_lane; return check_in_intersection || check_in_turns || check_in_general_lanes; 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 index 741a5d7b4761d..b73e242a9a70f 100644 --- 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 @@ -49,8 +49,8 @@ double calc_dist_from_pose_to_terminal_end( double calc_stopping_distance(const LCParamPtr & lc_param_ptr) { // v^2 = u^2 + 2ad - const auto min_lc_vel = lc_param_ptr->minimum_lane_changing_velocity; - const auto min_lon_acc = lc_param_ptr->min_longitudinal_acc; + const auto min_lc_vel = lc_param_ptr->trajectory.min_lane_changing_velocity; + const auto min_lon_acc = lc_param_ptr->trajectory.min_longitudinal_acc; const auto min_back_dist = std::abs((min_lc_vel * min_lc_vel) / (2 * min_lon_acc)); const auto param_back_dist = lc_param_ptr->backward_length_buffer_for_end_of_lane; @@ -104,7 +104,7 @@ double calc_dist_to_last_fit_width( double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr) { - const auto max_prepare_duration = common_data_ptr->lc_param_ptr->lane_change_prepare_duration; + const auto max_prepare_duration = common_data_ptr->lc_param_ptr->trajectory.prepare_duration; const auto ego_max_speed = common_data_ptr->bpp_param_ptr->max_vel; return max_prepare_duration * ego_max_speed; @@ -146,7 +146,7 @@ double calc_minimum_acceleration( const double min_acc_threshold, const double prepare_duration) { if (prepare_duration < eps) return -std::abs(min_acc_threshold); - const double min_lc_velocity = lane_change_parameters.minimum_lane_changing_velocity; + const double min_lc_velocity = lane_change_parameters.trajectory.min_lane_changing_velocity; const double acc = (min_lc_velocity - current_velocity) / prepare_duration; return std::clamp(acc, -std::abs(min_acc_threshold), -eps); } @@ -167,10 +167,10 @@ std::vector calc_min_lane_change_lengths( return {}; } - const auto min_vel = lc_param_ptr->minimum_lane_changing_velocity; - const auto min_max_lat_acc = lc_param_ptr->lane_change_lat_acc_map.find(min_vel); + const auto min_vel = lc_param_ptr->trajectory.min_lane_changing_velocity; + const auto min_max_lat_acc = lc_param_ptr->trajectory.lat_acc_map.find(min_vel); const auto max_lat_acc = std::get<1>(min_max_lat_acc); - const auto lat_jerk = lc_param_ptr->lane_changing_lateral_jerk; + const auto lat_jerk = lc_param_ptr->trajectory.lateral_jerk; std::vector min_lc_lengths{}; min_lc_lengths.reserve(shift_intervals.size()); @@ -195,24 +195,23 @@ std::vector calc_max_lane_change_lengths( return {}; } - const auto & lc_param_ptr = common_data_ptr->lc_param_ptr; - const auto lat_jerk = lc_param_ptr->lane_changing_lateral_jerk; - const auto t_prepare = lc_param_ptr->lane_change_prepare_duration; + const auto & params = common_data_ptr->lc_param_ptr->trajectory; + const auto lat_jerk = params.lateral_jerk; + const auto t_prepare = params.prepare_duration; const auto current_velocity = common_data_ptr->get_ego_speed(); const auto path_velocity = common_data_ptr->transient_data.current_path_velocity; const auto max_acc = calc_maximum_acceleration( - t_prepare, current_velocity, path_velocity, lc_param_ptr->max_longitudinal_acc); + t_prepare, current_velocity, path_velocity, params.max_longitudinal_acc); // TODO(Quda, Azu): should probably limit upper bound of velocity as well, but // disabled due failing evaluation tests. // const auto limit_vel = [&](const auto vel) { // const auto max_global_vel = common_data_ptr->bpp_param_ptr->max_vel; - // return std::clamp(vel, lc_param_ptr->minimum_lane_changing_velocity, max_global_vel); + // return std::clamp(vel, params.min_lane_changing_velocity, max_global_vel); // }; - auto vel = - std::max(common_data_ptr->get_ego_speed(), lc_param_ptr->minimum_lane_changing_velocity); + auto vel = std::max(common_data_ptr->get_ego_speed(), params.min_lane_changing_velocity); std::vector max_lc_lengths{}; @@ -222,7 +221,7 @@ std::vector calc_max_lane_change_lengths( vel = vel + max_acc * t_prepare; // lane changing section - const auto [min_lat_acc, max_lat_acc] = lc_param_ptr->lane_change_lat_acc_map.find(vel); + const auto [min_lat_acc, max_lat_acc] = params.lat_acc_map.find(vel); const auto t_lane_changing = autoware::motion_utils::calc_shift_time_from_jerk(shift_interval, lat_jerk, max_lat_acc); const auto lane_changing_length = @@ -307,8 +306,10 @@ std::pair calc_min_max_acceleration( const auto & bpp_params = *common_data_ptr->bpp_param_ptr; const auto current_ego_velocity = common_data_ptr->get_ego_speed(); - const auto min_accel_threshold = std::max(bpp_params.min_acc, lc_params.min_longitudinal_acc); - const auto max_accel_threshold = std::min(bpp_params.max_acc, lc_params.max_longitudinal_acc); + const auto min_accel_threshold = + std::max(bpp_params.min_acc, lc_params.trajectory.min_longitudinal_acc); + const auto max_accel_threshold = + std::min(bpp_params.max_acc, lc_params.trajectory.max_longitudinal_acc); // calculate minimum and maximum acceleration const auto min_acc = calc_minimum_acceleration( @@ -352,7 +353,7 @@ std::vector calc_lon_acceleration_samples( const auto & current_pose = common_data_ptr->get_ego_pose(); const auto & target_lanes = common_data_ptr->lanes_ptr->target; const auto goal_pose = common_data_ptr->route_handler_ptr->getGoalPose(); - const auto sampling_num = common_data_ptr->lc_param_ptr->longitudinal_acc_sampling_num; + const auto sampling_num = common_data_ptr->lc_param_ptr->trajectory.lon_acc_sampling_num; const auto [min_accel, max_accel] = calc_min_max_acceleration(common_data_ptr, max_path_velocity, prepare_duration); @@ -396,7 +397,7 @@ std::vector calc_prepare_durations(const CommonDataPtr & common_data_ptr const auto & lc_param_ptr = common_data_ptr->lc_param_ptr; const auto threshold = common_data_ptr->bpp_param_ptr->base_link2front + lc_param_ptr->min_length_for_turn_signal_activation; - const auto max_prepare_duration = lc_param_ptr->lane_change_prepare_duration; + const auto max_prepare_duration = lc_param_ptr->trajectory.prepare_duration; // TODO(Azu) this check seems to cause scenario failures. if (common_data_ptr->transient_data.dist_to_terminal_start >= threshold) { @@ -418,7 +419,7 @@ std::vector calc_prepare_phase_metrics( const double max_path_velocity, const double min_length_threshold, const double max_length_threshold) { - const auto & min_lc_vel = common_data_ptr->lc_param_ptr->minimum_lane_changing_velocity; + const auto & min_lc_vel = common_data_ptr->lc_param_ptr->trajectory.min_lane_changing_velocity; const auto & max_vel = common_data_ptr->bpp_param_ptr->max_vel; std::vector metrics; @@ -465,14 +466,15 @@ std::vector calc_shift_phase_metrics( const CommonDataPtr & common_data_ptr, const double shift_length, const double initial_velocity, const double max_path_velocity, const double lon_accel, const double max_length_threshold) { - const auto & min_lc_vel = common_data_ptr->lc_param_ptr->minimum_lane_changing_velocity; + const auto & min_lc_vel = common_data_ptr->lc_param_ptr->trajectory.min_lane_changing_velocity; const auto & max_vel = common_data_ptr->bpp_param_ptr->max_vel; // get lateral acceleration range const auto [min_lateral_acc, max_lateral_acc] = - common_data_ptr->lc_param_ptr->lane_change_lat_acc_map.find(initial_velocity); - const auto lateral_acc_resolution = std::abs(max_lateral_acc - min_lateral_acc) / - common_data_ptr->lc_param_ptr->lateral_acc_sampling_num; + common_data_ptr->lc_param_ptr->trajectory.lat_acc_map.find(initial_velocity); + const auto lateral_acc_resolution = + std::abs(max_lateral_acc - min_lateral_acc) / + common_data_ptr->lc_param_ptr->trajectory.lat_acc_sampling_num; std::vector metrics; @@ -490,7 +492,7 @@ std::vector calc_shift_phase_metrics( for (double lat_acc = min_lateral_acc; lat_acc < max_lateral_acc + eps; lat_acc += lateral_acc_resolution) { const auto lane_changing_duration = autoware::motion_utils::calc_shift_time_from_jerk( - shift_length, common_data_ptr->lc_param_ptr->lane_changing_lateral_jerk, lat_acc); + shift_length, common_data_ptr->lc_param_ptr->trajectory.lateral_jerk, lat_acc); const double lane_changing_accel = calc_lane_changing_acceleration( initial_velocity, max_path_velocity, lane_changing_duration, lon_accel); 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 49551aa73f635..ff8bb971405ad 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 @@ -613,7 +613,7 @@ std::vector convertToPredictedPath( const auto duration = lane_change_path.info.duration.sum(); const auto prepare_time = lane_change_path.info.duration.prepare; const auto & minimum_lane_changing_velocity = - lane_change_parameters.minimum_lane_changing_velocity; + lane_change_parameters.trajectory.min_lane_changing_velocity; const auto nearest_seg_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( @@ -784,8 +784,7 @@ bool passed_parked_objects( const auto lane_change_parameters = *common_data_ptr->lc_param_ptr; const auto & object_check_min_road_shoulder_width = lane_change_parameters.object_check_min_road_shoulder_width; - const auto & object_shiftable_ratio_threshold = - lane_change_parameters.object_shiftable_ratio_threshold; + const auto & object_shiftable_ratio_threshold = lane_change_parameters.th_object_shiftable_ratio; const auto & current_lane_path = common_data_ptr->current_lanes_path; if (objects.empty() || lane_change_path.path.points.empty() || current_lane_path.points.empty()) { @@ -918,7 +917,8 @@ ExtendedPredictedObject transform( { ExtendedPredictedObject extended_object(object); - const auto & time_resolution = lane_change_parameters.prediction_time_resolution; + const auto & time_resolution = + lane_change_parameters.safety.collision_check.prediction_time_resolution; const double obj_vel_norm = std::hypot(extended_object.initial_twist.linear.x, extended_object.initial_twist.linear.y); @@ -1032,10 +1032,10 @@ LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr) lanes_polygon.target = utils::lane_change::create_polygon(lanes->target, 0.0, std::numeric_limits::max()); - const auto & lc_param_ptr = common_data_ptr->lc_param_ptr; + const auto & params = common_data_ptr->lc_param_ptr->safety; const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets( - lanes->target, common_data_ptr->direction, lc_param_ptr->lane_expansion_left_offset, - lc_param_ptr->lane_expansion_right_offset); + lanes->target, common_data_ptr->direction, params.lane_expansion_left_offset, + params.lane_expansion_right_offset); lanes_polygon.expanded_target = utils::lane_change::create_polygon( expanded_target_lanes, 0.0, std::numeric_limits::max()); @@ -1184,7 +1184,7 @@ double get_min_dist_to_current_lanes_obj( for (const auto & object : filtered_objects.current_lane) { // check if stationary const auto obj_v = std::abs(object.initial_twist.linear.x); - if (obj_v > common_data_ptr->lc_param_ptr->stop_velocity_threshold) { + if (obj_v > common_data_ptr->lc_param_ptr->th_stop_velocity) { continue; } @@ -1297,7 +1297,7 @@ bool filter_target_lane_objects( const auto & current_lanes = common_data_ptr->lanes_ptr->current; const auto & vehicle_width = common_data_ptr->bpp_param_ptr->vehicle_info.vehicle_width_m; const auto & lanes_polygon = *common_data_ptr->lanes_polygon_ptr; - const auto stopped_obj_vel_th = common_data_ptr->lc_param_ptr->stopped_object_velocity_threshold; + const auto stopped_obj_vel_th = common_data_ptr->lc_param_ptr->safety.th_stopped_object_velocity; const auto is_lateral_far = std::invoke([&]() -> bool { const auto dist_object_to_current_lanes_center = From 53724037838c73575eaa7a7c794d729bf7d93f8c Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Tue, 26 Nov 2024 14:30:27 +0900 Subject: [PATCH 117/273] fix(obstacle_cruise_planner)!: remove stop reason (#9464) fix(obstacle_cruise_planner): remove stop reason Signed-off-by: satoshi-ota --- .../README.md | 11 ++-- .../planner_interface.hpp | 2 - .../obstacle_cruise_planner/type_alias.hpp | 5 -- .../launch/obstacle_cruise_planner.launch.xml | 1 - .../src/planner_interface.cpp | 52 ------------------- 5 files changed, 5 insertions(+), 66 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/README.md b/planning/autoware_obstacle_cruise_planner/README.md index 1cb8128110e7c..42a569c07ddb2 100644 --- a/planning/autoware_obstacle_cruise_planner/README.md +++ b/planning/autoware_obstacle_cruise_planner/README.md @@ -23,12 +23,11 @@ The `autoware_obstacle_cruise_planner` package has following modules. ### Output topics -| Name | Type | Description | -| ------------------------------- | ---------------------------------------------- | ------------------------------------- | -| `~/output/trajectory` | autoware_planning_msgs::Trajectory | output trajectory | -| `~/output/velocity_limit` | tier4_planning_msgs::VelocityLimit | velocity limit for cruising | -| `~/output/clear_velocity_limit` | tier4_planning_msgs::VelocityLimitClearCommand | clear command for velocity limit | -| `~/output/stop_reasons` | tier4_planning_msgs::StopReasonArray | reasons that make the vehicle to stop | +| Name | Type | Description | +| ------------------------------- | ---------------------------------------------- | -------------------------------- | +| `~/output/trajectory` | autoware_planning_msgs::Trajectory | output trajectory | +| `~/output/velocity_limit` | tier4_planning_msgs::VelocityLimit | velocity limit for cruising | +| `~/output/clear_velocity_limit` | tier4_planning_msgs::VelocityLimitClearCommand | clear command for velocity limit | ## Design diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp index e4fb1c6cfe36d..ef6ae1662dcee 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp @@ -54,7 +54,6 @@ class PlannerInterface slow_down_param_(SlowDownParam(node)), stop_param_(StopParam(node, longitudinal_info)) { - stop_reasons_pub_ = node.create_publisher("~/output/stop_reasons", 1); velocity_factors_pub_ = node.create_publisher("/planning/velocity_factors/obstacle_cruise", 1); stop_speed_exceeded_pub_ = @@ -146,7 +145,6 @@ class PlannerInterface stop_watch_; // Publishers - rclcpp::Publisher::SharedPtr stop_reasons_pub_; rclcpp::Publisher::SharedPtr velocity_factors_pub_; rclcpp::Publisher::SharedPtr stop_speed_exceeded_pub_; rclcpp::Publisher::SharedPtr metrics_pub_; diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp index 541a8281b2f1d..04badd2a956ef 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp @@ -30,8 +30,6 @@ #include "sensor_msgs/msg/point_cloud2.hpp" #include "tier4_debug_msgs/msg/float32_stamped.hpp" #include "tier4_debug_msgs/msg/float64_stamped.hpp" -#include "tier4_planning_msgs/msg/stop_factor.hpp" -#include "tier4_planning_msgs/msg/stop_reason_array.hpp" #include "tier4_planning_msgs/msg/stop_speed_exceeded.hpp" #include "tier4_planning_msgs/msg/velocity_limit.hpp" #include "tier4_planning_msgs/msg/velocity_limit_clear_command.hpp" @@ -58,9 +56,6 @@ using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; using tier4_debug_msgs::msg::Float32Stamped; using tier4_debug_msgs::msg::Float64Stamped; -using tier4_planning_msgs::msg::StopFactor; -using tier4_planning_msgs::msg::StopReason; -using tier4_planning_msgs::msg::StopReasonArray; using tier4_planning_msgs::msg::StopSpeedExceeded; using tier4_planning_msgs::msg::VelocityLimit; using tier4_planning_msgs::msg::VelocityLimitClearCommand; diff --git a/planning/autoware_obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml b/planning/autoware_obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml index aaf6db3e36613..189cd44379276 100644 --- a/planning/autoware_obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml +++ b/planning/autoware_obstacle_cruise_planner/launch/obstacle_cruise_planner.launch.xml @@ -31,6 +31,5 @@ - diff --git a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp index 61946a8e4b37f..bfff561e3ffe2 100644 --- a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp @@ -39,54 +39,6 @@ StopSpeedExceeded createStopSpeedExceededMsg( return msg; } -tier4_planning_msgs::msg::StopReasonArray makeStopReasonArray( - const PlannerData & planner_data, const geometry_msgs::msg::Pose & stop_pose, - const StopObstacle & stop_obstacle) -{ - // create header - std_msgs::msg::Header header; - header.frame_id = "map"; - header.stamp = planner_data.current_time; - - // create stop factor - StopFactor stop_factor; - stop_factor.stop_pose = stop_pose; - geometry_msgs::msg::Point stop_factor_point = stop_obstacle.collision_point; - stop_factor_point.z = stop_pose.position.z; - stop_factor.dist_to_stop_pose = autoware::motion_utils::calcSignedArcLength( - planner_data.traj_points, planner_data.ego_pose.position, stop_pose.position); - stop_factor.stop_factor_points.emplace_back(stop_factor_point); - - // create stop reason stamped - StopReason stop_reason_msg; - stop_reason_msg.reason = StopReason::OBSTACLE_STOP; - stop_reason_msg.stop_factors.emplace_back(stop_factor); - - // create stop reason array - StopReasonArray stop_reason_array; - stop_reason_array.header = header; - stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); - return stop_reason_array; -} - -StopReasonArray makeEmptyStopReasonArray(const rclcpp::Time & current_time) -{ - // create header - std_msgs::msg::Header header; - header.frame_id = "map"; - header.stamp = current_time; - - // create stop reason stamped - StopReason stop_reason_msg; - stop_reason_msg.reason = StopReason::OBSTACLE_STOP; - - // create stop reason array - StopReasonArray stop_reason_array; - stop_reason_array.header = header; - stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); - return stop_reason_array; -} - double calcMinimumDistanceToStop( const double initial_vel, const double max_acc, const double min_acc) { @@ -226,7 +178,6 @@ std::vector PlannerInterface::generateStopTrajectory( : std::abs(vehicle_info_.min_longitudinal_offset_m); if (stop_obstacles.empty()) { - stop_reasons_pub_->publish(makeEmptyStopReasonArray(planner_data.current_time)); velocity_factors_pub_->publish( obstacle_cruise_utils::makeVelocityFactorArray(planner_data.current_time)); // delete marker @@ -381,9 +332,6 @@ std::vector PlannerInterface::generateStopTrajectory( // Publish Stop Reason const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose; - const auto stop_reasons_msg = - makeStopReasonArray(planner_data, stop_pose, *determined_stop_obstacle); - stop_reasons_pub_->publish(stop_reasons_msg); velocity_factors_pub_->publish(obstacle_cruise_utils::makeVelocityFactorArray( planner_data.current_time, PlanningBehavior::ROUTE_OBSTACLE, stop_pose)); // Store stop reason debug data From 824a7d543630e15287a3bce2e34970bdfe84448d Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Tue, 26 Nov 2024 16:23:09 +0900 Subject: [PATCH 118/273] fix(autoware_ekf_localizer): publish `processing_time_ms` (#9443) Fixed to publish processing_time_ms Signed-off-by: Shintaro Sakoda --- localization/autoware_ekf_localizer/README.md | 1 + .../include/autoware/ekf_localizer/ekf_localizer.hpp | 3 +++ .../launch/ekf_localizer.launch.xml | 2 ++ .../autoware_ekf_localizer/src/ekf_localizer.cpp | 10 ++++++++++ 4 files changed, 16 insertions(+) diff --git a/localization/autoware_ekf_localizer/README.md b/localization/autoware_ekf_localizer/README.md index fb367e5b42286..aad65da2516d1 100644 --- a/localization/autoware_ekf_localizer/README.md +++ b/localization/autoware_ekf_localizer/README.md @@ -54,6 +54,7 @@ This package includes the following features: | `ekf_twist` | `geometry_msgs::msg::TwistStamped` | Estimated twist. | | `ekf_twist_with_covariance` | `geometry_msgs::msg::TwistWithCovarianceStamped` | The estimated twist with covariance. | | `diagnostics` | `diagnostics_msgs::msg::DiagnosticArray` | The diagnostic information. | +| `debug/processing_time_ms` | `tier4_debug_msgs::msg::Float64Stamped` | The processing time [ms]. | ### Published TF diff --git a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp index d61faa39a93a0..1b437f26e9c7d 100644 --- a/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp +++ b/localization/autoware_ekf_localizer/include/autoware/ekf_localizer/ekf_localizer.hpp @@ -85,6 +85,8 @@ class EKFLocalizer : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_biased_pose_cov_; //!< @brief diagnostics publisher rclcpp::Publisher::SharedPtr pub_diag_; + //!< @brief processing_time publisher + rclcpp::Publisher::SharedPtr pub_processing_time_; //!< @brief initial pose subscriber rclcpp::Subscription::SharedPtr sub_initialpose_; //!< @brief measurement pose with covariance subscriber @@ -185,6 +187,7 @@ class EKFLocalizer : public rclcpp::Node std_srvs::srv::SetBool::Response::SharedPtr res); autoware::universe_utils::StopWatch stop_watch_; + autoware::universe_utils::StopWatch stop_watch_timer_cb_; friend class EKFLocalizerTestSuite; // for test code }; diff --git a/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml b/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml index 2942abe1ff11e..76ac35bcba38e 100644 --- a/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml +++ b/localization/autoware_ekf_localizer/launch/ekf_localizer.launch.xml @@ -16,6 +16,7 @@ + @@ -32,6 +33,7 @@ + diff --git a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp index 70ae4c04436ec..7e2606cdc3860 100644 --- a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp +++ b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp @@ -73,6 +73,8 @@ EKFLocalizer::EKFLocalizer(const rclcpp::NodeOptions & node_options) pub_biased_pose_cov_ = create_publisher( "ekf_biased_pose_with_covariance", 1); pub_diag_ = this->create_publisher("/diagnostics", 10); + pub_processing_time_ = + create_publisher("debug/processing_time_ms", 1); sub_initialpose_ = create_subscription( "initialpose", 1, std::bind(&EKFLocalizer::callback_initial_pose, this, _1)); sub_pose_with_cov_ = create_subscription( @@ -129,6 +131,8 @@ void EKFLocalizer::update_predict_frequency(const rclcpp::Time & current_time) */ void EKFLocalizer::timer_callback() { + stop_watch_timer_cb_.tic(); + const rclcpp::Time current_time = this->now(); if (!is_activated_) { @@ -219,6 +223,12 @@ void EKFLocalizer::timer_callback() /* publish ekf result */ publish_estimate_result(current_ekf_pose, current_biased_ekf_pose, current_ekf_twist); publish_diagnostics(current_ekf_pose, current_time); + + /* publish processing time */ + const double elapsed_time = stop_watch_timer_cb_.toc(); + pub_processing_time_->publish(tier4_debug_msgs::build() + .stamp(current_time) + .data(elapsed_time)); } /* From f1d967d181599f3cd8f6450eed9a048e19a2193a Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 26 Nov 2024 16:33:34 +0900 Subject: [PATCH 119/273] feat(lane_change): parse predicted objects for lane change test (RT1-8251) (#9256) * RT1-8251 parse predicted objects Signed-off-by: Zulfaqar Azmi * fix pre-commit and build error Signed-off-by: Zulfaqar Azmi * add additional test and fix test failure Signed-off-by: Zulfaqar Azmi * fix lint_cmake failure Signed-off-by: Zulfaqar Azmi * use expect instead Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> --- .../CMakeLists.txt | 5 +- .../test/test_lane_change_scene.cpp | 41 +- .../test_data/test_object_filter.yaml | 1838 +++++++++++++++++ 3 files changed, 1880 insertions(+), 4 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test_data/test_object_filter.yaml 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 6ae84881477e8..d1b6bfed868f0 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 @@ -28,4 +28,7 @@ if(BUILD_TESTING) target_include_directories(test_${PROJECT_NAME} PRIVATE src) endif() -ament_auto_package(INSTALL_TO_SHARE config) +ament_auto_package(INSTALL_TO_SHARE + config + test_data +) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp index 6f285190c4169..0570349bc3df5 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp @@ -21,12 +21,13 @@ #include -#include "autoware_planning_msgs/msg/lanelet_route.hpp" +#include #include #include +using autoware::behavior_path_planner::FilteredLanesObjects; using autoware::behavior_path_planner::LaneChangeModuleManager; using autoware::behavior_path_planner::LaneChangeModuleType; using autoware::behavior_path_planner::NormalLaneChange; @@ -40,6 +41,7 @@ using autoware::test_utils::get_absolute_path_to_config; using autoware::test_utils::get_absolute_path_to_lanelet_map; using autoware::test_utils::get_absolute_path_to_route; using autoware_map_msgs::msg::LaneletMapBin; +using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::LaneletRoute; using geometry_msgs::msg::Pose; using tier4_planning_msgs::msg::PathWithLaneId; @@ -64,8 +66,13 @@ class TestNormalLaneChange : public ::testing::Test ego_pose_ = autoware::test_utils::createPose(-50.0, 1.75, 0.0, 0.0, 0.0, 0.0); planner_data_->self_odometry = set_odometry(ego_pose_); - planner_data_->dynamic_object = - std::make_shared(); + const auto objects_file = + ament_index_cpp::get_package_share_directory("autoware_behavior_path_lane_change_module") + + "/test_data/test_object_filter.yaml"; + + YAML::Node yaml_node = YAML::LoadFile(objects_file); + const auto objects = autoware::test_utils::parse(yaml_node); + planner_data_->dynamic_object = std::make_shared(objects); } void init_module() @@ -131,6 +138,11 @@ class TestNormalLaneChange : public ::testing::Test return std::make_shared(odom); } + [[nodiscard]] FilteredLanesObjects & get_filtered_objects() const + { + return normal_lane_change_->filtered_objects_; + } + void set_previous_approved_path() { normal_lane_change_->prev_module_output_.path = create_previous_approved_path(); @@ -212,6 +224,29 @@ TEST_F(TestNormalLaneChange, testGetPathWhenInvalid) ASSERT_FALSE(lc_status.is_valid_path); } +TEST_F(TestNormalLaneChange, testFilteredObjects) +{ + constexpr auto is_approved = true; + ego_pose_ = autoware::test_utils::createPose(1.0, 1.75, 0.0, 0.0, 0.0, 0.0); + planner_data_->self_odometry = set_odometry(ego_pose_); + set_previous_approved_path(); + + normal_lane_change_->update_lanes(!is_approved); + normal_lane_change_->update_filtered_objects(); + + const auto & filtered_objects = get_filtered_objects(); + + // Note: There's 1 stopping object in current lanes, however, it was filtered out. + const auto filtered_size = + filtered_objects.current_lane.size() + filtered_objects.target_lane_leading.size() + + filtered_objects.target_lane_trailing.size() + filtered_objects.others.size(); + EXPECT_EQ(filtered_size, planner_data_->dynamic_object->objects.size()); + EXPECT_EQ(filtered_objects.current_lane.size(), 0); + EXPECT_EQ(filtered_objects.target_lane_leading.size(), 2); + EXPECT_EQ(filtered_objects.target_lane_trailing.size(), 0); + EXPECT_EQ(filtered_objects.others.size(), 2); +} + TEST_F(TestNormalLaneChange, testGetPathWhenValid) { constexpr auto is_approved = true; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test_data/test_object_filter.yaml b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test_data/test_object_filter.yaml new file mode 100644 index 0000000000000..3ef05a0cd1024 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test_data/test_object_filter.yaml @@ -0,0 +1,1838 @@ +header: + stamp: + sec: 1730959270 + nanosec: 700904396 + frame_id: map +objects: + - object_id: + uuid: + - 57 + - 234 + - 237 + - 159 + - 195 + - 229 + - 66 + - 71 + - 21 + - 44 + - 68 + - 122 + - 144 + - 106 + - 13 + - 190 + existence_probability: 0.0 + classification: + - label: 3 + probability: 1.0 + kinematics: + initial_pose_with_covariance: + pose: + position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + covariance: + - 0.12314689855728007 + - -0.0061611584403754 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - -0.0061611584403753975 + - 0.0028632078333398737 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0007922605681590912 + initial_twist_with_covariance: + twist: + linear: + x: 0.0022924032607949227 + y: 1.0376500541998356e-07 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: 3.908788083083818e-08 + covariance: + - 0.7401171867683597 + - 3.350119623596881e-05 + - 0.0 + - 0.0 + - 0.0 + - 1.2619772541445709e-05 + - 3.350119623596881e-05 + - 4.254924999186505e-08 + - 0.0 + - 0.0 + - 0.0 + - 1.6028139799077814e-08 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 1.261977254144571e-05 + - 1.6028139799077817e-08 + - 0.0 + - 0.0 + - 0.0 + - 6.037738984069024e-09 + initial_acceleration_with_covariance: + accel: + linear: + x: 0.0 + y: 0.0 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: 0.0 + covariance: + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + predicted_paths: + - path: + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + - position: + x: -26.277885137995664 + y: -1.894734886474639 + z: 0.8911920935795934 + orientation: + x: 0.0 + y: 0.0 + z: -0.025541935117105664 + w: 0.9996737515562133 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 1.0 + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 10.61863710330581 + y: 2.6 + z: 1.8699817255447553 + - object_id: + uuid: + - 141 + - 149 + - 211 + - 87 + - 79 + - 101 + - 139 + - 123 + - 68 + - 8 + - 135 + - 54 + - 236 + - 22 + - 42 + - 245 + existence_probability: 0.0 + classification: + - label: 3 + probability: 1.0 + kinematics: + initial_pose_with_covariance: + pose: + position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + covariance: + - 0.12346140759139482 + - 0.0001740656821558044 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0001740656821558044 + - 0.0025486884508984387 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0007923887288897377 + initial_twist_with_covariance: + twist: + linear: + x: 0.01149754330094817 + y: -3.1578956564191503e-07 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: -1.340071831009146e-07 + covariance: + - 0.7401171745434685 + - -2.0327885143452095e-05 + - 0.0 + - 0.0 + - 0.0 + - -8.6262591385362e-06 + - -2.0327885143452095e-05 + - 1.0315766321625746e-06 + - 0.0 + - 0.0 + - 0.0 + - 4.377556881837847e-07 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - -8.6262591385362e-06 + - 4.3775568818378476e-07 + - 0.0 + - 0.0 + - 0.0 + - 1.8576423366195293e-07 + initial_acceleration_with_covariance: + accel: + linear: + x: 0.0 + y: 0.0 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: 0.0 + covariance: + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + predicted_paths: + - path: + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + - position: + x: -10.7607993411875 + y: -1.9485222301582967 + z: 1.8354702975479853 + orientation: + x: 0.0 + y: 0.0 + z: 0.0007335045608968457 + w: 0.9999997309854934 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 1.0 + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 9.426048912739507 + y: 2.6538046848726022 + z: 3.370528331600673 + - object_id: + uuid: + - 71 + - 249 + - 231 + - 94 + - 71 + - 17 + - 61 + - 160 + - 244 + - 177 + - 239 + - 139 + - 84 + - 132 + - 224 + - 157 + existence_probability: 0.0 + classification: + - label: 3 + probability: 1.0 + kinematics: + initial_pose_with_covariance: + pose: + position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + covariance: + - 0.12325225128472374 + - -0.004992467682066607 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - -0.004992467682066607 + - 0.002755512431768385 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0007924339915606306 + initial_twist_with_covariance: + twist: + linear: + x: -0.008145866229493542 + y: 2.7177554489085472e-06 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: 1.553003113662027e-06 + covariance: + - 0.7401113329295389 + - -0.00024692616733628655 + - 0.0 + - 0.0 + - 0.0 + - -0.0001411006670493066 + - -0.0002469261673362865 + - 6.212518114314515e-07 + - 0.0 + - 0.0 + - 0.0 + - 3.550010351036865e-07 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - -0.0001411006670493066 + - 3.5500103510368645e-07 + - 0.0 + - 0.0 + - 0.0 + - 2.028577343449637e-07 + initial_acceleration_with_covariance: + accel: + linear: + x: 0.0 + y: 0.0 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: 0.0 + covariance: + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + predicted_paths: + - path: + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + - position: + x: 8.951931667607116 + y: 2.0177028806099195 + z: 1.9961166695683017 + orientation: + x: 0.0 + y: 0.0 + z: -0.02050547163810942 + w: 0.9997897407119652 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 1.0 + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 7.0 + y: 2.5391492564805107 + z: 2.988733287063526 + - object_id: + uuid: + - 131 + - 104 + - 242 + - 151 + - 76 + - 97 + - 188 + - 81 + - 236 + - 166 + - 159 + - 74 + - 95 + - 82 + - 96 + - 160 + existence_probability: 0.0 + classification: + - label: 3 + probability: 1.0 + kinematics: + initial_pose_with_covariance: + pose: + position: + x: -15.804813657329067 + y: 6.927734802768457 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598655 + w: 0.9996716560741284 + covariance: + - 0.12314192052841168 + - 0.006207305811351786 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.006207305811351787 + - 0.002868420675357726 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0007923396833076764 + initial_twist_with_covariance: + twist: + linear: + x: -0.008710890141645097 + y: -1.4990440656518e-06 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: -5.645388351563947e-07 + covariance: + - 0.7401166659649231 + - 0.00012736585105397946 + - 0.0 + - 0.0 + - 0.0 + - 4.7965880950572506e-05 + - 0.00012736585105397946 + - 6.178150020515808e-07 + - 0.0 + - 0.0 + - 0.0 + - 2.3266865170417227e-07 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.010000000000000002 + - 0.0 + - 4.796588095057249e-05 + - 2.326686517041723e-07 + - 0.0 + - 0.0 + - 0.0 + - 8.762283419158182e-08 + initial_acceleration_with_covariance: + accel: + linear: + x: 0.0 + y: 0.0 + z: 0.0 + angular: + x: 0.0 + y: 0.0 + z: 0.0 + covariance: + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + - 0.0 + predicted_paths: + - path: + - position: + x: -15.804813657329067 + y: 6.927734802768457 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.809163344604654 + y: 6.92751092125665 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.813513031880241 + y: 6.927287039744844 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.81786271915583 + y: 6.927063158233037 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.822212406431417 + y: 6.92683927672123 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.826562093707004 + y: 6.926615395209423 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.830911780982591 + y: 6.926391513697617 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.835261468258178 + y: 6.926167632185811 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.839611155533767 + y: 6.925943750674004 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.843960842809354 + y: 6.925719869162197 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.848310530084941 + y: 6.9254959876503905 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.852660217360528 + y: 6.925272106138584 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.857009904636115 + y: 6.925048224626777 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.861359591911704 + y: 6.92482434311497 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.865709279187291 + y: 6.924600461603164 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.870058966462878 + y: 6.924376580091357 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.874408653738465 + y: 6.92415269857955 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.878758341014052 + y: 6.923928817067743 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.88310802828964 + y: 6.923704935555937 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.887457715565228 + y: 6.92348105404413 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.891807402840815 + y: 6.923257172532324 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.896157090116402 + y: 6.923033291020517 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.900506777391989 + y: 6.9228094095087105 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.904856464667578 + y: 6.922585527996904 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.909206151943165 + y: 6.922361646485097 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.913555839218752 + y: 6.92213776497329 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.917905526494339 + y: 6.9219138834614835 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.922255213769926 + y: 6.921690001949677 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.926604901045513 + y: 6.92146612043787 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.930954588321102 + y: 6.921242238926063 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + - position: + x: -15.935304275596689 + y: 6.9210183574142565 + z: 1.7960623786923189 + orientation: + x: 0.0 + y: 0.0 + z: 0.025623817865598652 + w: 0.9996716560741286 + time_step: + sec: 0 + nanosec: 500000000 + confidence: 1.0 + shape: + type: 0 + footprint: + points: [] + dimensions: + x: 10.621370735187906 + y: 2.6779142303492427 + z: 3.4752818839000423 From d6e854e4ef81fa8bb42a3bc9ed97caeebcf619ad Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Tue, 26 Nov 2024 16:47:57 +0900 Subject: [PATCH 120/273] docs(autoware_autonomous_emergency_braking): enhance IMU path generation section with constraints and algorithm details (#9458) Signed-off-by: Kyoichi Sugahara --- .../README.md | 73 ++++++++++++++++++- 1 file changed, 69 insertions(+), 4 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/README.md b/control/autoware_autonomous_emergency_braking/README.md index f0f4a6c9f7014..d3ee7d4e1aa29 100644 --- a/control/autoware_autonomous_emergency_braking/README.md +++ b/control/autoware_autonomous_emergency_braking/README.md @@ -60,7 +60,7 @@ We do not activate AEB module if it satisfies the following conditions. ### 2. Generate a predicted path of the ego vehicle -#### IMU path generation +#### 2.1 Overview of IMU Path Generation AEB generates a predicted footprint path based on current velocity and current angular velocity obtained from attached sensors. Note that if `use_imu_path` is `false`, it skips this step. This predicted path is generated as: @@ -72,16 +72,81 @@ $$ where $v$ and $\omega$ are current longitudinal velocity and angular velocity respectively. $dt$ is time interval that users can define in advance with the `imu_prediction_time_interval` parameter. The IMU path is generated considering a time horizon, defined by the `imu_prediction_time_horizon` parameter. -Since the IMU path generation only uses the ego vehicle's current angular velocity, disregarding the MPC's planner steering, the shape of the IMU path tends to get distorted quite easily and protrude out of the ego vehicle's current lane, possibly causing unwanted emergency stops. That is why it is not recommended to use a big `imu_prediction_time_horizon`. To fix this issue, the IMU path's length can be cut short by tuning the `max_generated_imu_path_length` parameter, the IMU path generation will be cut short once its length surpasses this parameter's value. +#### 2.2 Constraints and Countermeasures in IMU Path Generation -It is also possible to limit the IMU path length based on the predicted lateral deviation of the vehicle by setting the `limit_imu_path_lat_dev` parameter flag to "true", and setting a threshold lateral deviation with the `imu_path_lat_dev_threshold` parameter. That way, the AEB will generate a predicted IMU path until a given predicted ego pose surpasses the lateral deviation threshold, and the IMU path will be cut short when the ego vehicle is turning relatively fast. +Since the IMU path generation only uses the ego vehicle's current angular velocity, disregarding the MPC's planner steering, the shape of the IMU path tends to get distorted quite easily and protrude out of the ego vehicle's current lane, possibly causing unwanted emergency stops. There are two countermeasures for this issue: -The advantage of setting a lateral deviation limit with the `limit_imu_path_lat_dev` parameter is that the `imu_prediction_time_horizon` and the `max_generated_imu_path_length` can be increased without worries about the IMU predicted path deforming beyond a certain threshold. The downside is that the IMU path will be cut short when the ego has a high angular velocity, in said cases, the AEB module would mostly rely on the MPC path to prevent or mitigate collisions. If it is assumed the ego vehicle will mostly travel along the centerline of its lanelets, it can be useful to set the lateral deviation threshold parameter `imu_path_lat_dev_threshold` to be equal to or smaller than the average lanelet width divided by 2, that way, the chance of the IMU predicted path leaving the current ego lanelet is smaller, and it is possible to increase the `imu_prediction_time_horizon` to prevent frontal collisions when the ego is mostly traveling in a straight line. +1. Control using the `max_generated_imu_path_length` parameter + + - Generation stops when path length exceeds the set value + - Avoid using a large `imu_prediction_time_horizon` + +2. Control based on lateral deviation + - Set the `limit_imu_path_lat_dev` parameter to "true" + - Set deviation threshold using `imu_path_lat_dev_threshold` + - Path generation stops when lateral deviation exceeds the threshold + +#### 2.3 Advantages and Limitations of Lateral Deviation Control + +The advantage of setting a lateral deviation limit with the `limit_imu_path_lat_dev` parameter is that the `imu_prediction_time_horizon` and the `max_generated_imu_path_length` can be increased without worries about the IMU predicted path deforming beyond a certain threshold. The downside is that the IMU path will be cut short when the ego has a high angular velocity, in said cases, the AEB module would mostly rely on the MPC path to prevent or mitigate collisions. + +If it is assumed the ego vehicle will mostly travel along the centerline of its lanelets, it can be useful to set the lateral deviation threshold parameter `imu_path_lat_dev_threshold` to be equal to or smaller than the average lanelet width divided by 2, that way, the chance of the IMU predicted path leaving the current ego lanelet is smaller, and it is possible to increase the `imu_prediction_time_horizon` to prevent frontal collisions when the ego is mostly traveling in a straight line. The lateral deviation is measured using the ego vehicle's current position as a reference, and it measures the distance of the furthermost vertex of the predicted ego footprint to the predicted path. The following image illustrates how the lateral deviation of a given ego pose is measured. ![measuring_lat_dev](./image/measuring-lat-dev-on-imu-path.drawio.svg) +#### 2.4 IMU Path Generation Algorithm + +##### 2.4.1 Selection of Lateral Deviation Check Points + +Select vehicle vertices for lateral deviation checks based on the following conditions: + +- Forward motion ($v > 0$) + - Right turn ($\omega > 0$): Right front vertex + - Left turn ($\omega < 0$): Left front vertex +- Reverse motion ($v < 0$) + - Right turn ($\omega > 0$): Right rear vertex + - Left turn ($\omega < 0$): Left rear vertex +- Straight motion ($\omega = 0$): Check both front/rear vertices depending on forward/reverse motion + +##### 2.4.2 Path Generation Process + +Execute the following steps at each time step: + +1. State Update + + - Calculate next position $(x_{k+1}, y_{k+1})$ and yaw angle $\theta_{k+1}$ based on current velocity $v$ and angular velocity $\omega$ + - Time interval $dt$ is based on the `imu_prediction_time_interval` parameter + +2. Vehicle Footprint Generation + + - Place vehicle footprint at calculated position + - Calculate check point coordinates + +3. Lateral Deviation Calculation + + - Calculate lateral deviation from selected vertex to path + - Update path length and elapsed time + +4. Evaluation of Termination Conditions + +##### 2.4.3 Termination Conditions + +Path generation terminates when any of the following conditions are met: + +1. Basic Termination Conditions (both must be satisfied) + + - Predicted time exceeds `imu_prediction_time_horizon` + - AND path length exceeds `min_generated_imu_path_length` + +2. Path Length Termination Condition + + - Path length exceeds `max_generated_imu_path_length` + +3. Lateral Deviation Termination Condition (when `limit_imu_path_lat_dev = true`) + - Lateral deviation of selected vertex exceeds `imu_path_lat_dev_threshold` + #### MPC path generation If the `use_predicted_trajectory` parameter is set to true, the AEB module will directly use the predicted path from the MPC as a base to generate a footprint path. It will copy the ego poses generated by the MPC until a given time horizon. The `mpc_prediction_time_horizon` parameter dictates how far ahead in the future the MPC path will predict the ego vehicle's movement. Both the IMU footprint path and the MPC footprint path can be used at the same time. From c8bbeff4d5dc1efd16795724b4048717db7b7169 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 17:07:31 +0900 Subject: [PATCH 121/273] fix(autoware_mission_planner): fix clang-diagnostic-error (#9432) Signed-off-by: veqcc --- .../src/mission_planner/service_utils.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp b/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp index b12b5f635275c..8b6e5c9916705 100644 --- a/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/service_utils.hpp @@ -19,6 +19,7 @@ #include +#include #include #include From e5ad03af80a786f23726e6c2940ed82867056b00 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 17:07:59 +0900 Subject: [PATCH 122/273] fix(simple_planning_simulator): fix clang-diagnostic-delete-non-abstract-non-virtual-dtor (#9448) Signed-off-by: veqcc --- .../vehicle_model/sim_model_interface.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp index 5ca886b1b5847..bab4531484aa6 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp @@ -50,7 +50,7 @@ class SimModelInterface /** * @brief destructor */ - ~SimModelInterface() = default; + virtual ~SimModelInterface() = default; /** * @brief get state vector of model From 4fcd6da9feed8438805c7404992e20fae870744a Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 20:36:29 +0900 Subject: [PATCH 123/273] fix(autoware_freespace_planning_algorithms): fix clang-diagnostic-unused-const-variable (#9433) Signed-off-by: veqcc --- .../autoware_freespace_planning_algorithms/src/reeds_shepp.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp b/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp index ee6d1cb8d1d9a..7b5acb40892e2 100644 --- a/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/reeds_shepp.cpp @@ -91,7 +91,7 @@ using autoware::freespace_planning_algorithms::ReedsSheppStateSpace; const double pi = M_PI; const double twopi = 2. * pi; -const double RS_EPS = 1e-6; +[[maybe_unused]] const double RS_EPS = 1e-6; // used only in assertions const double ZERO = 10 * std::numeric_limits::epsilon(); inline double mod2pi(double x) From 9a28f08ef2b7e2883952f0f62a8a6bf3a7a5d4bd Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 20:37:15 +0900 Subject: [PATCH 124/273] fix(autoware_mpc_lateral_controller): fix clang-tidy errors (#9436) Signed-off-by: veqcc --- .../include/autoware/mpc_lateral_controller/mpc.hpp | 6 ++---- .../mpc_lateral_controller/mpc_lateral_controller.hpp | 4 ++-- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp index eedac39f37bd4..81c8b71683092 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp @@ -227,8 +227,6 @@ class MPC bool m_is_forward_shift = true; // Flag indicating if the shift is in the forward direction. - double m_min_prediction_length = 5.0; // Minimum prediction distance. - rclcpp::Publisher::SharedPtr m_debug_frenet_predicted_trajectory_pub; rclcpp::Publisher::SharedPtr m_debug_resampled_reference_trajectory_pub; /** @@ -405,7 +403,7 @@ class MPC template inline bool fail_warn_throttle(Args &&... args) const { - RCLCPP_WARN_THROTTLE(m_logger, *m_clock, 3000, args...); + RCLCPP_WARN_THROTTLE(m_logger, *m_clock, 3000, "%s", args...); return false; } @@ -413,7 +411,7 @@ class MPC template inline void warn_throttle(Args &&... args) const { - RCLCPP_WARN_THROTTLE(m_logger, *m_clock, 3000, args...); + RCLCPP_WARN_THROTTLE(m_logger, *m_clock, 3000, "%s", args...); } public: diff --git a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp index fe68d150b5b9a..d7442f64b028a 100644 --- a/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp +++ b/control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc_lateral_controller.hpp @@ -292,13 +292,13 @@ class MpcLateralController : public trajectory_follower::LateralControllerBase template inline void info_throttle(Args &&... args) { - RCLCPP_INFO_THROTTLE(logger_, *clock_, 5000, args...); + RCLCPP_INFO_THROTTLE(logger_, *clock_, 5000, "%s", args...); } template inline void warn_throttle(Args &&... args) { - RCLCPP_WARN_THROTTLE(logger_, *clock_, 5000, args...); + RCLCPP_WARN_THROTTLE(logger_, *clock_, 5000, "%s", args...); } }; } // namespace autoware::motion::control::mpc_lateral_controller From 96951e7968a5f9f36c29982ff45f919d040ecd7e Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 20:37:34 +0900 Subject: [PATCH 125/273] fix(autoware_osqp_interface): fix clang-tidy errors (#9440) Signed-off-by: veqcc --- common/autoware_osqp_interface/CMakeLists.txt | 2 +- common/autoware_osqp_interface/src/osqp_interface.cpp | 2 +- common/autoware_qp_interface/CMakeLists.txt | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/common/autoware_osqp_interface/CMakeLists.txt b/common/autoware_osqp_interface/CMakeLists.txt index e9ed0ce25f2f8..b770af659e52a 100644 --- a/common/autoware_osqp_interface/CMakeLists.txt +++ b/common/autoware_osqp_interface/CMakeLists.txt @@ -26,7 +26,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ${OSQP_INTERFACE_LIB_SRC} ${OSQP_INTERFACE_LIB_HEADERS} ) -target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast -Wno-error=useless-cast) +target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast) target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC diff --git a/common/autoware_osqp_interface/src/osqp_interface.cpp b/common/autoware_osqp_interface/src/osqp_interface.cpp index 9ebf132f65028..ceeae626222ca 100644 --- a/common/autoware_osqp_interface/src/osqp_interface.cpp +++ b/common/autoware_osqp_interface/src/osqp_interface.cpp @@ -430,6 +430,6 @@ void OSQPInterface::logUnsolvedStatus(const std::string & prefix_message) const output_message += "Optimization failed due to " + status_message; // log with warning - RCLCPP_WARN(rclcpp::get_logger("osqp_interface"), output_message.c_str()); + RCLCPP_WARN(rclcpp::get_logger("osqp_interface"), "%s", output_message.c_str()); } } // namespace autoware::osqp_interface diff --git a/common/autoware_qp_interface/CMakeLists.txt b/common/autoware_qp_interface/CMakeLists.txt index d2f2d6347cb3d..1df75d2d719a0 100644 --- a/common/autoware_qp_interface/CMakeLists.txt +++ b/common/autoware_qp_interface/CMakeLists.txt @@ -30,7 +30,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ${QP_INTERFACE_LIB_SRC} ${QP_INTERFACE_LIB_HEADERS} ) -target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast -Wno-error=useless-cast) +target_compile_options(${PROJECT_NAME} PRIVATE -Wno-error=old-style-cast) target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC From 635ad2da8d57c988ec72130d493ea244df32f6a1 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 26 Nov 2024 20:40:28 +0900 Subject: [PATCH 126/273] fix(tier4_adapi_rviz_plugin): fix clang-diagnostic-unused-lambda-capture (#9439) Signed-off-by: veqcc --- common/tier4_adapi_rviz_plugin/src/state_panel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/tier4_adapi_rviz_plugin/src/state_panel.cpp b/common/tier4_adapi_rviz_plugin/src/state_panel.cpp index 6d2980a7f2c4a..0525f5fdc1a09 100644 --- a/common/tier4_adapi_rviz_plugin/src/state_panel.cpp +++ b/common/tier4_adapi_rviz_plugin/src/state_panel.cpp @@ -280,7 +280,7 @@ void StatePanel::onInitialize() void StatePanel::onOperationMode(const OperationModeState::ConstSharedPtr msg) { - auto changeButtonState = [this]( + auto changeButtonState = []( QPushButton * button, const bool is_desired_mode_available, const uint8_t current_mode = OperationModeState::UNKNOWN, const uint8_t desired_mode = OperationModeState::STOP) { From 340a5af9fb54af1d978e1126413c8602015085d7 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 26 Nov 2024 20:54:30 +0900 Subject: [PATCH 127/273] fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-overloaded-virtual (#9400) Signed-off-by: kobayu858 --- .../autoware/behavior_path_lane_change_module/interface.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp index bd309dd35a260..07920f83fd980 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/interface.hpp @@ -93,6 +93,8 @@ class LaneChangeInterface : public SceneModuleInterface MarkerArray getModuleVirtualWall() override; protected: + using SceneModuleInterface::updateRTCStatus; + std::shared_ptr parameters_; std::unique_ptr module_type_; From 56ed0551b3c0469986f99bbba4a9fce1331ec3d3 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 26 Nov 2024 20:54:54 +0900 Subject: [PATCH 128/273] fix(autoware_lidar_centerpoint): fix clang-diagnostic-unused-private-field (#9471) Signed-off-by: kobayu858 --- .../include/autoware/lidar_centerpoint/node.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp index eb056ed14c57f..a49451fde9d0d 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/node.hpp @@ -51,7 +51,6 @@ class LidarCenterPointNode : public rclcpp::Node rclcpp::Subscription::SharedPtr pointcloud_sub_; rclcpp::Publisher::SharedPtr objects_pub_; - float score_threshold_{0.0}; std::vector class_names_; bool has_variance_{false}; bool has_twist_{false}; From 2244f286fc9eca8fb246a11c39cc4dd17c97d022 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 26 Nov 2024 20:56:28 +0900 Subject: [PATCH 129/273] fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (#9472) Signed-off-by: kobayu858 --- .../roi_detected_object_fusion/node.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp index ea15a2df5efe2..7103537ec852d 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_detected_object_fusion/node.hpp @@ -57,7 +57,7 @@ class RoiDetectedObjectFusionNode void publish(const DetectedObjects & output_msg) override; - bool out_of_scope(const DetectedObject & obj); + bool out_of_scope(const DetectedObject & obj) override; private: struct From f9159c1b0d93e654b9e602f62588ad754007e354 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 26 Nov 2024 21:00:31 +0900 Subject: [PATCH 130/273] fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-error (#9402) Signed-off-by: kobayu858 --- .../src/utils/calculation.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) 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 index b73e242a9a70f..9cbf9d4beb5ff 100644 --- 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 @@ -355,8 +355,10 @@ std::vector calc_lon_acceleration_samples( const auto goal_pose = common_data_ptr->route_handler_ptr->getGoalPose(); const auto sampling_num = common_data_ptr->lc_param_ptr->trajectory.lon_acc_sampling_num; - const auto [min_accel, max_accel] = + const auto min_max_accel = calc_min_max_acceleration(common_data_ptr, max_path_velocity, prepare_duration); + const auto & min_accel = min_max_accel.first; + const auto & max_accel = min_max_accel.second; const auto is_sampling_required = std::invoke([&]() -> bool { if (max_accel < 0.0 || transient_data.is_ego_stuck) return true; From 5b5a93c92a1cc46680ece34bd4e8ebbb94cbb60e Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 27 Nov 2024 09:28:57 +0900 Subject: [PATCH 131/273] fix(autoware_pointcloud_preprocessor): fix clang-diagnostic-inconsistent-missing-override (#9445) Signed-off-by: veqcc --- .../crop_box_filter/crop_box_filter_node.hpp | 4 ++-- .../outlier_filter/ring_outlier_filter_node.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp index 2a983835e4e55..2eb0f2505642a 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/crop_box_filter/crop_box_filter_node.hpp @@ -67,8 +67,8 @@ namespace autoware::pointcloud_preprocessor class CropBoxFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: - virtual void filter( - const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output); + void filter( + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; // TODO(sykwer): Temporary Implementation: Remove this interface when all the filter nodes conform // to new API diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp index a19c0c1e257b2..c898cbacf33ea 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp @@ -44,8 +44,8 @@ class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Fil using InputPointType = autoware::point_types::PointXYZIRCAEDT; using OutputPointType = autoware::point_types::PointXYZIRC; - virtual void filter( - const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output); + void filter( + const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output) override; // TODO(sykwer): Temporary Implementation: Remove this interface when all the filter nodes conform // to new API From f23916f6e2881be89dc800e5da5f701c61a2066e Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Wed, 27 Nov 2024 11:26:56 +0900 Subject: [PATCH 132/273] fix(autoware_trajectory): autoware_trajectory bug (#9475) fix autoware_trajectory bug Signed-off-by: Y.Hisaki --- common/autoware_trajectory/src/path_point.cpp | 2 +- common/autoware_trajectory/src/path_point_with_lane_id.cpp | 2 +- common/autoware_trajectory/src/pose.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/common/autoware_trajectory/src/path_point.cpp b/common/autoware_trajectory/src/path_point.cpp index af1e9286b533d..4a2ac80b749bd 100644 --- a/common/autoware_trajectory/src/path_point.cpp +++ b/common/autoware_trajectory/src/path_point.cpp @@ -76,7 +76,7 @@ std::vector Trajectory::restore(const size_t & min_points) points.reserve(bases.size()); for (const auto & s : bases) { PointType p; - p.pose = Trajectory::compute(s); + p.pose = Trajectory::compute(s - start_); p.longitudinal_velocity_mps = static_cast(this->longitudinal_velocity_mps.compute(s)); p.lateral_velocity_mps = static_cast(this->lateral_velocity_mps.compute(s)); p.heading_rate_rps = static_cast(this->heading_rate_rps.compute(s)); diff --git a/common/autoware_trajectory/src/path_point_with_lane_id.cpp b/common/autoware_trajectory/src/path_point_with_lane_id.cpp index 6c983c4dfa0d3..c3d7441fef405 100644 --- a/common/autoware_trajectory/src/path_point_with_lane_id.cpp +++ b/common/autoware_trajectory/src/path_point_with_lane_id.cpp @@ -65,7 +65,7 @@ std::vector Trajectory::restore(const size_t & min_points) points.reserve(bases.size()); for (const auto & s : bases) { PointType p; - p.point = BaseClass::compute(s); + p.point = BaseClass::compute(s - start_); p.lane_ids = lane_ids.compute(s); points.emplace_back(p); } diff --git a/common/autoware_trajectory/src/pose.cpp b/common/autoware_trajectory/src/pose.cpp index 35eca81981f89..3906ee17fa2eb 100644 --- a/common/autoware_trajectory/src/pose.cpp +++ b/common/autoware_trajectory/src/pose.cpp @@ -92,7 +92,7 @@ std::vector Trajectory::restore(const size_t & min_points) points.reserve(bases.size()); for (const auto & s : bases) { PointType p; - p.position = BaseClass::compute(s); + p.position = BaseClass::compute(s - start_); p.orientation = orientation_interpolator_->compute(s); points.emplace_back(p); } From 12a86f63dd865c4a0661286c5b4f354260299944 Mon Sep 17 00:00:00 2001 From: "Kem (TiankuiXian)" <1041084556@qq.com> Date: Wed, 27 Nov 2024 11:57:54 +0900 Subject: [PATCH 133/273] refactor(evaluators, autoware_universe_utils): rename Stat class to Accumulator and move it to autoware_universe_utils (#9459) * add Accumulator class to autoware_universe_utils Signed-off-by: xtk8532704 <1041084556@qq.com> * use Accumulator on all evaluators. Signed-off-by: xtk8532704 <1041084556@qq.com> * pre-commit Signed-off-by: xtk8532704 <1041084556@qq.com> * found and fixed a bug. add more tests. Signed-off-by: xtk8532704 <1041084556@qq.com> * pre-commit Signed-off-by: xtk8532704 <1041084556@qq.com> * Update common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp Co-authored-by: Kosuke Takeuchi Signed-off-by: xtk8532704 <1041084556@qq.com> --------- Signed-off-by: xtk8532704 <1041084556@qq.com> Co-authored-by: Kosuke Takeuchi --- .../universe_utils/math/accumulator.hpp | 26 +++--- .../test/src/math/test_accumulator.cpp | 64 +++++++++++++ .../autoware_planning_evaluator/README.md | 4 +- .../metrics/deviation_metrics.hpp | 15 +-- .../metrics/metrics_utils.hpp | 2 - .../metrics/obstacle_metrics.hpp | 8 +- .../metrics/stability_metrics.hpp | 7 +- .../metrics/trajectory_metrics.hpp | 20 ++-- .../planning_evaluator/metrics_calculator.hpp | 7 +- .../motion_evaluator_node.hpp | 3 +- .../planning_evaluator_node.hpp | 7 +- .../src/metrics/deviation_metrics.cpp | 24 ++--- .../src/metrics/obstacle_metrics.cpp | 9 +- .../src/metrics/stability_metrics.cpp | 8 +- .../src/metrics/trajectory_metrics.cpp | 33 +++---- .../src/metrics_calculator.cpp | 4 +- .../src/planning_evaluator_node.cpp | 3 +- .../kinematic_evaluator_node.hpp | 9 +- .../metrics/kinematic_metrics.hpp | 5 +- .../metrics_calculator.hpp | 9 +- .../include/kinematic_evaluator/stat.hpp | 93 ------------------- .../src/kinematic_evaluator_node.cpp | 4 +- .../src/metrics/kinematic_metrics.cpp | 4 +- .../src/metrics_calculator.cpp | 4 +- .../localization_evaluator_node.hpp | 9 +- .../metrics/localization_metrics.hpp | 11 ++- .../metrics_calculator.hpp | 7 +- .../include/localization_evaluator/stat.hpp | 93 ------------------- .../src/localization_evaluator_node.cpp | 4 +- .../src/metrics/localization_metrics.cpp | 12 +-- .../src/metrics_calculator.cpp | 4 +- .../metrics/detection_count.hpp | 1 - .../metrics/deviation_metrics.hpp | 2 - .../metrics/metric.hpp | 9 +- .../metrics_calculator.hpp | 1 - .../perception_online_evaluator_node.hpp | 5 +- .../perception_online_evaluator/stat.hpp | 93 ------------------- .../src/metrics_calculator.cpp | 6 +- .../src/perception_online_evaluator_node.cpp | 2 +- 39 files changed, 215 insertions(+), 416 deletions(-) rename evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/stat.hpp => common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp (69%) create mode 100644 common/autoware_universe_utils/test/src/math/test_accumulator.cpp delete mode 100644 evaluator/kinematic_evaluator/include/kinematic_evaluator/stat.hpp delete mode 100644 evaluator/localization_evaluator/include/localization_evaluator/stat.hpp delete mode 100644 evaluator/perception_online_evaluator/include/perception_online_evaluator/stat.hpp diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/stat.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp similarity index 69% rename from evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/stat.hpp rename to common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp index 5f63f29a96f26..eb460cc685891 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/stat.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp @@ -1,4 +1,4 @@ -// Copyright 2021 Tier IV, Inc. +// Copyright 2021-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. @@ -15,17 +15,17 @@ #include #include -#ifndef AUTOWARE__PLANNING_EVALUATOR__STAT_HPP_ -#define AUTOWARE__PLANNING_EVALUATOR__STAT_HPP_ +#ifndef AUTOWARE__UNIVERSE_UTILS__MATH__ACCUMULATOR_HPP_ +#define AUTOWARE__UNIVERSE_UTILS__MATH__ACCUMULATOR_HPP_ -namespace planning_diagnostics +namespace autoware::universe_utils { /** - * @brief class to incrementally build statistics + * @brief class to accumulate statistical data, supporting min, max and mean. * @typedef T type of the values (default to double) */ template -class Stat +class Accumulator { public: /** @@ -65,11 +65,11 @@ class Stat unsigned int count() const { return count_; } template - friend std::ostream & operator<<(std::ostream & os, const Stat & stat); + friend std::ostream & operator<<(std::ostream & os, const Accumulator & accumulator); private: T min_ = std::numeric_limits::max(); - T max_ = std::numeric_limits::min(); + T max_ = std::numeric_limits::lowest(); long double mean_ = 0.0; unsigned int count_ = 0; }; @@ -78,16 +78,16 @@ class Stat * @brief overload << operator for easy print to output stream */ template -std::ostream & operator<<(std::ostream & os, const Stat & stat) +std::ostream & operator<<(std::ostream & os, const Accumulator & accumulator) { - if (stat.count() == 0) { + if (accumulator.count() == 0) { os << "None None None"; } else { - os << stat.min() << " " << stat.max() << " " << stat.mean(); + os << accumulator.min() << " " << accumulator.max() << " " << accumulator.mean(); } return os; } -} // namespace planning_diagnostics +} // namespace autoware::universe_utils -#endif // AUTOWARE__PLANNING_EVALUATOR__STAT_HPP_ +#endif // AUTOWARE__UNIVERSE_UTILS__MATH__ACCUMULATOR_HPP_ diff --git a/common/autoware_universe_utils/test/src/math/test_accumulator.cpp b/common/autoware_universe_utils/test/src/math/test_accumulator.cpp new file mode 100644 index 0000000000000..89630454d5f19 --- /dev/null +++ b/common/autoware_universe_utils/test/src/math/test_accumulator.cpp @@ -0,0 +1,64 @@ +// 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/math/accumulator.hpp" + +#include + +TEST(accumulator, empty) +{ + autoware::universe_utils::Accumulator acc; + + EXPECT_DOUBLE_EQ(acc.mean(), 0.0); + EXPECT_DOUBLE_EQ(acc.min(), std::numeric_limits::max()); + EXPECT_DOUBLE_EQ(acc.max(), std::numeric_limits::lowest()); + EXPECT_EQ(acc.count(), 0); +} + +TEST(accumulator, addValues) +{ + autoware::universe_utils::Accumulator acc; + acc.add(100.0); + + EXPECT_DOUBLE_EQ(acc.mean(), 100.0); + EXPECT_DOUBLE_EQ(acc.min(), 100.0); + EXPECT_DOUBLE_EQ(acc.max(), 100.0); + EXPECT_EQ(acc.count(), 1); +} + +TEST(accumulator, positiveValues) +{ + autoware::universe_utils::Accumulator acc; + acc.add(10.0); + acc.add(40.0); + acc.add(10.0); + + EXPECT_DOUBLE_EQ(acc.mean(), 20.0); + EXPECT_DOUBLE_EQ(acc.min(), 10.0); + EXPECT_DOUBLE_EQ(acc.max(), 40.0); + EXPECT_EQ(acc.count(), 3); +} + +TEST(accumulator, negativeValues) +{ + autoware::universe_utils::Accumulator acc; + acc.add(-10.0); + acc.add(-40.0); + acc.add(-10.0); + + EXPECT_DOUBLE_EQ(acc.mean(), -20.0); + EXPECT_DOUBLE_EQ(acc.min(), -40.0); + EXPECT_DOUBLE_EQ(acc.max(), -10.0); + EXPECT_EQ(acc.count(), 3); +} diff --git a/evaluator/autoware_planning_evaluator/README.md b/evaluator/autoware_planning_evaluator/README.md index d09949bd69b0e..30ae1559ca9da 100644 --- a/evaluator/autoware_planning_evaluator/README.md +++ b/evaluator/autoware_planning_evaluator/README.md @@ -20,7 +20,7 @@ which is also responsible for calculating metrics. ### Stat -Each metric is calculated using a `Stat` instance which contains +Each metric is calculated using a `autoware::universe_utils::Accumulator` instance which contains the minimum, maximum, and mean values calculated for the metric as well as the number of values measured. @@ -35,7 +35,7 @@ The `MetricsCalculator` is responsible for calculating metric statistics through calls to function: ```C++ -Stat MetricsCalculator::calculate(const Metric metric, const Trajectory & traj) const; +Accumulator MetricsCalculator::calculate(const Metric metric, const Trajectory & traj) const; ``` Adding a new metric `M` requires the following steps: diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp index 8d7cfbd30d604..59866c96ad702 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/deviation_metrics.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ #define AUTOWARE__PLANNING_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ -#include "autoware/planning_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" @@ -24,6 +24,7 @@ namespace planning_diagnostics { namespace metrics { +using autoware::universe_utils::Accumulator; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using geometry_msgs::msg::Point; @@ -35,7 +36,7 @@ using geometry_msgs::msg::Pose; * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcLateralDeviation(const Trajectory & ref, const Trajectory & traj); +Accumulator calcLateralDeviation(const Trajectory & ref, const Trajectory & traj); /** * @brief calculate yaw deviation of the given trajectory from the reference trajectory @@ -43,7 +44,7 @@ Stat calcLateralDeviation(const Trajectory & ref, const Trajectory & tra * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcYawDeviation(const Trajectory & ref, const Trajectory & traj); +Accumulator calcYawDeviation(const Trajectory & ref, const Trajectory & traj); /** * @brief calculate velocity deviation of the given trajectory from the reference trajectory @@ -51,7 +52,7 @@ Stat calcYawDeviation(const Trajectory & ref, const Trajectory & traj); * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj); +Accumulator calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj); /** * @brief calculate longitudinal deviation of the given ego pose from the modified goal pose @@ -59,7 +60,7 @@ Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & tr * @param [in] target_point target point * @return calculated statistics */ -Stat calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point); +Accumulator calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point); /** * @brief calculate lateral deviation of the given ego pose from the modified goal pose @@ -67,7 +68,7 @@ Stat calcLongitudinalDeviation(const Pose & base_pose, const Point & tar * @param [in] target_point target point * @return calculated statistics */ -Stat calcLateralDeviation(const Pose & base_pose, const Point & target_point); +Accumulator calcLateralDeviation(const Pose & base_pose, const Point & target_point); /** * @brief calculate yaw deviation of the given ego pose from the modified goal pose @@ -75,7 +76,7 @@ Stat calcLateralDeviation(const Pose & base_pose, const Point & target_p * @param [in] target_pose target pose * @return calculated statistics */ -Stat calcYawDeviation(const Pose & base_pose, const Pose & target_pose); +Accumulator calcYawDeviation(const Pose & base_pose, const Pose & target_pose); } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metrics_utils.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metrics_utils.hpp index 2ade316ba7ad5..0006e49c3338a 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metrics_utils.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/metrics_utils.hpp @@ -15,8 +15,6 @@ #ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__METRICS_UTILS_HPP_ #define AUTOWARE__PLANNING_EVALUATOR__METRICS__METRICS_UTILS_HPP_ -#include "autoware/planning_evaluator/stat.hpp" - #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/obstacle_metrics.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/obstacle_metrics.hpp index c4d468b4dacd5..55e46bf710450 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/obstacle_metrics.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/obstacle_metrics.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__OBSTACLE_METRICS_HPP_ #define AUTOWARE__PLANNING_EVALUATOR__METRICS__OBSTACLE_METRICS_HPP_ -#include "autoware/planning_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" @@ -24,6 +24,7 @@ namespace planning_diagnostics { namespace metrics { +using autoware::universe_utils::Accumulator; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::Trajectory; @@ -33,7 +34,8 @@ using autoware_planning_msgs::msg::Trajectory; * @param [in] traj trajectory * @return calculated statistics */ -Stat calcDistanceToObstacle(const PredictedObjects & obstacles, const Trajectory & traj); +Accumulator calcDistanceToObstacle( + const PredictedObjects & obstacles, const Trajectory & traj); /** * @brief calculate the time to collision of the trajectory with the given obstacles @@ -42,7 +44,7 @@ Stat calcDistanceToObstacle(const PredictedObjects & obstacles, const Tr * @param [in] traj trajectory * @return calculated statistics */ -Stat calcTimeToCollision( +Accumulator calcTimeToCollision( const PredictedObjects & obstacles, const Trajectory & traj, const double distance_threshold); } // namespace metrics diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp index f1e93380d34d6..38f388feeadda 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/stability_metrics.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__STABILITY_METRICS_HPP_ #define AUTOWARE__PLANNING_EVALUATOR__METRICS__STABILITY_METRICS_HPP_ -#include "autoware/planning_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" @@ -23,6 +23,7 @@ namespace planning_diagnostics { namespace metrics { +using autoware::universe_utils::Accumulator; using autoware_planning_msgs::msg::Trajectory; /** @@ -31,7 +32,7 @@ using autoware_planning_msgs::msg::Trajectory; * @param [in] traj2 second trajectory * @return calculated statistics */ -Stat calcFrechetDistance(const Trajectory & traj1, const Trajectory & traj2); +Accumulator calcFrechetDistance(const Trajectory & traj1, const Trajectory & traj2); /** * @brief calculate the lateral distance between two trajectories @@ -39,7 +40,7 @@ Stat calcFrechetDistance(const Trajectory & traj1, const Trajectory & tr * @param [in] traj2 second trajectory * @return calculated statistics */ -Stat calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2); +Accumulator calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2); } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/trajectory_metrics.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/trajectory_metrics.hpp index 14a6a5c451619..c530a8d6d8b05 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/trajectory_metrics.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics/trajectory_metrics.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__PLANNING_EVALUATOR__METRICS__TRAJECTORY_METRICS_HPP_ #define AUTOWARE__PLANNING_EVALUATOR__METRICS__TRAJECTORY_METRICS_HPP_ -#include "autoware/planning_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" #include "autoware_planning_msgs/msg/trajectory_point.hpp" @@ -24,6 +24,7 @@ namespace planning_diagnostics { namespace metrics { +using autoware::universe_utils::Accumulator; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -33,56 +34,57 @@ using autoware_planning_msgs::msg::TrajectoryPoint; * @param [in] min_dist_threshold minimum distance between successive points * @return calculated statistics */ -Stat calcTrajectoryRelativeAngle(const Trajectory & traj, const double min_dist_threshold); +Accumulator calcTrajectoryRelativeAngle( + const Trajectory & traj, const double min_dist_threshold); /** * @brief calculate metric for the distance between trajectory points * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcTrajectoryInterval(const Trajectory & traj); +Accumulator calcTrajectoryInterval(const Trajectory & traj); /** * @brief calculate curvature metric * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcTrajectoryCurvature(const Trajectory & traj); +Accumulator calcTrajectoryCurvature(const Trajectory & traj); /** * @brief calculate length of the trajectory [m] * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcTrajectoryLength(const Trajectory & traj); +Accumulator calcTrajectoryLength(const Trajectory & traj); /** * @brief calculate duration of the trajectory [s] * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcTrajectoryDuration(const Trajectory & traj); +Accumulator calcTrajectoryDuration(const Trajectory & traj); /** * @brief calculate velocity metrics for the trajectory * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcTrajectoryVelocity(const Trajectory & traj); +Accumulator calcTrajectoryVelocity(const Trajectory & traj); /** * @brief calculate acceleration metrics for the trajectory * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcTrajectoryAcceleration(const Trajectory & traj); +Accumulator calcTrajectoryAcceleration(const Trajectory & traj); /** * @brief calculate jerk metrics for the trajectory * @param [in] traj input trajectory * @return calculated statistics */ -Stat calcTrajectoryJerk(const Trajectory & traj); +Accumulator calcTrajectoryJerk(const Trajectory & traj); } // namespace metrics } // namespace planning_diagnostics diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp index f500a435edba1..97d23cad10af2 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/metrics_calculator.hpp @@ -16,7 +16,7 @@ #define AUTOWARE__PLANNING_EVALUATOR__METRICS_CALCULATOR_HPP_ #include "autoware/planning_evaluator/metrics/metric.hpp" #include "autoware/planning_evaluator/parameters.hpp" -#include "autoware/planning_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include "autoware_perception_msgs/msg/predicted_objects.hpp" #include "autoware_planning_msgs/msg/pose_with_uuid_stamped.hpp" @@ -28,6 +28,7 @@ namespace planning_diagnostics { +using autoware::universe_utils::Accumulator; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::PoseWithUuidStamped; using autoware_planning_msgs::msg::Trajectory; @@ -47,8 +48,8 @@ class MetricsCalculator * @param [in] metric Metric enum value * @return string describing the requested metric */ - std::optional> calculate(const Metric metric, const Trajectory & traj) const; - std::optional> calculate( + std::optional> calculate(const Metric metric, const Trajectory & traj) const; + std::optional> calculate( const Metric metric, const Pose & base_pose, const Pose & target_pose) const; /** diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/motion_evaluator_node.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/motion_evaluator_node.hpp index ed9c975436ba5..8193472c4dc39 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/motion_evaluator_node.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/motion_evaluator_node.hpp @@ -16,7 +16,7 @@ #define AUTOWARE__PLANNING_EVALUATOR__MOTION_EVALUATOR_NODE_HPP_ #include "autoware/planning_evaluator/metrics_calculator.hpp" -#include "autoware/planning_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -33,6 +33,7 @@ namespace planning_diagnostics { +using autoware::universe_utils::Accumulator; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp index 065d168b02d38..0f4b8f7289a4f 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp @@ -16,7 +16,7 @@ #define AUTOWARE__PLANNING_EVALUATOR__PLANNING_EVALUATOR_NODE_HPP_ #include "autoware/planning_evaluator/metrics_calculator.hpp" -#include "autoware/planning_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -43,6 +43,7 @@ #include namespace planning_diagnostics { +using autoware::universe_utils::Accumulator; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::PoseWithUuidStamped; using autoware_planning_msgs::msg::Trajectory; @@ -98,7 +99,7 @@ class PlanningEvaluatorNode : public rclcpp::Node /** * @brief publish the given metric statistic */ - void AddMetricMsg(const Metric & metric, const Stat & metric_stat); + void AddMetricMsg(const Metric & metric, const Accumulator & metric_stat); /** * @brief publish current ego lane info @@ -162,7 +163,7 @@ class PlanningEvaluatorNode : public rclcpp::Node // Metrics std::vector metrics_; std::deque stamps_; - std::array>, static_cast(Metric::SIZE)> metric_stats_; + std::array>, static_cast(Metric::SIZE)> metric_stats_; rclcpp::TimerBase::SharedPtr timer_; std::optional prev_acc_stamped_{std::nullopt}; diff --git a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp index 8ce8a009652d8..7e2217a49ef87 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/deviation_metrics.cpp @@ -25,9 +25,9 @@ namespace metrics using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -Stat calcLateralDeviation(const Trajectory & ref, const Trajectory & traj) +Accumulator calcLateralDeviation(const Trajectory & ref, const Trajectory & traj) { - Stat stat; + Accumulator stat; if (ref.points.empty() || traj.points.empty()) { return stat; @@ -45,9 +45,9 @@ Stat calcLateralDeviation(const Trajectory & ref, const Trajectory & tra return stat; } -Stat calcYawDeviation(const Trajectory & ref, const Trajectory & traj) +Accumulator calcYawDeviation(const Trajectory & ref, const Trajectory & traj) { - Stat stat; + Accumulator stat; if (ref.points.empty() || traj.points.empty()) { return stat; @@ -64,9 +64,9 @@ Stat calcYawDeviation(const Trajectory & ref, const Trajectory & traj) return stat; } -Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj) +Accumulator calcVelocityDeviation(const Trajectory & ref, const Trajectory & traj) { - Stat stat; + Accumulator stat; if (ref.points.empty() || traj.points.empty()) { return stat; @@ -81,23 +81,23 @@ Stat calcVelocityDeviation(const Trajectory & ref, const Trajectory & tr return stat; } -Stat calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point) +Accumulator calcLongitudinalDeviation(const Pose & base_pose, const Point & target_point) { - Stat stat; + Accumulator stat; stat.add(std::abs(autoware::universe_utils::calcLongitudinalDeviation(base_pose, target_point))); return stat; } -Stat calcLateralDeviation(const Pose & base_pose, const Point & target_point) +Accumulator calcLateralDeviation(const Pose & base_pose, const Point & target_point) { - Stat stat; + Accumulator stat; stat.add(std::abs(autoware::universe_utils::calcLateralDeviation(base_pose, target_point))); return stat; } -Stat calcYawDeviation(const Pose & base_pose, const Pose & target_pose) +Accumulator calcYawDeviation(const Pose & base_pose, const Pose & target_pose) { - Stat stat; + Accumulator stat; stat.add(std::abs(autoware::universe_utils::calcYawDeviation(base_pose, target_pose))); return stat; } diff --git a/evaluator/autoware_planning_evaluator/src/metrics/obstacle_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/obstacle_metrics.cpp index 3cdaf3d7eaaae..0afc8d982a7e9 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/obstacle_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/obstacle_metrics.cpp @@ -30,9 +30,10 @@ namespace metrics using autoware::universe_utils::calcDistance2d; using autoware_planning_msgs::msg::TrajectoryPoint; -Stat calcDistanceToObstacle(const PredictedObjects & obstacles, const Trajectory & traj) +Accumulator calcDistanceToObstacle( + const PredictedObjects & obstacles, const Trajectory & traj) { - Stat stat; + Accumulator stat; for (const TrajectoryPoint & p : traj.points) { double min_dist = std::numeric_limits::max(); for (const auto & object : obstacles.objects) { @@ -45,10 +46,10 @@ Stat calcDistanceToObstacle(const PredictedObjects & obstacles, const Tr return stat; } -Stat calcTimeToCollision( +Accumulator calcTimeToCollision( const PredictedObjects & obstacles, const Trajectory & traj, const double distance_threshold) { - Stat stat; + Accumulator stat; /** TODO(Maxime CLEMENT): * this implementation assumes static obstacles and does not work for dynamic obstacles */ diff --git a/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp index 4d1c02faa406f..e6ede0d07b9b3 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/stability_metrics.cpp @@ -29,9 +29,9 @@ namespace metrics { using autoware_planning_msgs::msg::TrajectoryPoint; -Stat calcFrechetDistance(const Trajectory & traj1, const Trajectory & traj2) +Accumulator calcFrechetDistance(const Trajectory & traj1, const Trajectory & traj2) { - Stat stat; + Accumulator stat; if (traj1.points.empty() || traj2.points.empty()) { return stat; @@ -58,9 +58,9 @@ Stat calcFrechetDistance(const Trajectory & traj1, const Trajectory & tr return stat; } -Stat calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2) +Accumulator calcLateralDistance(const Trajectory & traj1, const Trajectory & traj2) { - Stat stat; + Accumulator stat; if (traj1.points.empty()) { return stat; } diff --git a/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp b/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp index 4526865ced97d..bd5eed06f96f8 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics/trajectory_metrics.cpp @@ -23,18 +23,19 @@ namespace metrics using autoware::universe_utils::calcCurvature; using autoware::universe_utils::calcDistance2d; -Stat calcTrajectoryInterval(const Trajectory & traj) +Accumulator calcTrajectoryInterval(const Trajectory & traj) { - Stat stat; + Accumulator stat; for (size_t i = 1; i < traj.points.size(); ++i) { stat.add(calcDistance2d(traj.points.at(i), traj.points.at(i - 1))); } return stat; } -Stat calcTrajectoryRelativeAngle(const Trajectory & traj, const double min_dist_threshold) +Accumulator calcTrajectoryRelativeAngle( + const Trajectory & traj, const double min_dist_threshold) { - Stat stat; + Accumulator stat; // We need at least three points to compute relative angle const size_t relative_angle_points_num = 3; if (traj.points.size() < relative_angle_points_num) { @@ -79,9 +80,9 @@ Stat calcTrajectoryRelativeAngle(const Trajectory & traj, const double m return stat; } -Stat calcTrajectoryCurvature(const Trajectory & traj) +Accumulator calcTrajectoryCurvature(const Trajectory & traj) { - Stat stat; + Accumulator stat; // We need at least three points to compute curvature if (traj.points.size() < 3) { return stat; @@ -111,18 +112,18 @@ Stat calcTrajectoryCurvature(const Trajectory & traj) return stat; } -Stat calcTrajectoryLength(const Trajectory & traj) +Accumulator calcTrajectoryLength(const Trajectory & traj) { double length = 0.0; for (size_t i = 1; i < traj.points.size(); ++i) { length += calcDistance2d(traj.points.at(i), traj.points.at(i - 1)); } - Stat stat; + Accumulator stat; stat.add(length); return stat; } -Stat calcTrajectoryDuration(const Trajectory & traj) +Accumulator calcTrajectoryDuration(const Trajectory & traj) { double duration = 0.0; for (size_t i = 0; i + 1 < traj.points.size(); ++i) { @@ -132,32 +133,32 @@ Stat calcTrajectoryDuration(const Trajectory & traj) duration += length / std::abs(velocity); } } - Stat stat; + Accumulator stat; stat.add(duration); return stat; } -Stat calcTrajectoryVelocity(const Trajectory & traj) +Accumulator calcTrajectoryVelocity(const Trajectory & traj) { - Stat stat; + Accumulator stat; for (TrajectoryPoint p : traj.points) { stat.add(p.longitudinal_velocity_mps); } return stat; } -Stat calcTrajectoryAcceleration(const Trajectory & traj) +Accumulator calcTrajectoryAcceleration(const Trajectory & traj) { - Stat stat; + Accumulator stat; for (TrajectoryPoint p : traj.points) { stat.add(p.acceleration_mps2); } return stat; } -Stat calcTrajectoryJerk(const Trajectory & traj) +Accumulator calcTrajectoryJerk(const Trajectory & traj) { - Stat stat; + Accumulator stat; for (size_t i = 0; i + 1 < traj.points.size(); ++i) { const double vel = traj.points.at(i).longitudinal_velocity_mps; if (vel != 0) { diff --git a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp index 8658a666b4976..6e057bcc9fc3d 100644 --- a/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp +++ b/evaluator/autoware_planning_evaluator/src/metrics_calculator.cpp @@ -22,7 +22,7 @@ #include "autoware/universe_utils/geometry/geometry.hpp" namespace planning_diagnostics { -std::optional> MetricsCalculator::calculate( +std::optional> MetricsCalculator::calculate( const Metric metric, const Trajectory & traj) const { // Functions to calculate trajectory metrics @@ -74,7 +74,7 @@ std::optional> MetricsCalculator::calculate( } } -std::optional> MetricsCalculator::calculate( +std::optional> MetricsCalculator::calculate( const Metric metric, const Pose & base_pose, const Pose & target_pose) const { // Functions to calculate pose metrics diff --git a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp index e5e1c947a735c..d770833bc40a8 100644 --- a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp @@ -198,7 +198,8 @@ void PlanningEvaluatorNode::AddKinematicStateMetricMsg( return; } -void PlanningEvaluatorNode::AddMetricMsg(const Metric & metric, const Stat & metric_stat) +void PlanningEvaluatorNode::AddMetricMsg( + const Metric & metric, const Accumulator & metric_stat) { const std::string base_name = metric_to_str.at(metric) + "/"; MetricMsg metric_msg; diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/kinematic_evaluator_node.hpp b/evaluator/kinematic_evaluator/include/kinematic_evaluator/kinematic_evaluator_node.hpp index 16b4230fc4656..d401f63649468 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/kinematic_evaluator_node.hpp +++ b/evaluator/kinematic_evaluator/include/kinematic_evaluator/kinematic_evaluator_node.hpp @@ -15,8 +15,8 @@ #ifndef KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_ #define KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_ +#include "autoware/universe_utils/math/accumulator.hpp" #include "kinematic_evaluator/metrics_calculator.hpp" -#include "kinematic_evaluator/stat.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -33,6 +33,7 @@ namespace kinematic_diagnostics { +using autoware::universe_utils::Accumulator; using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; @@ -55,7 +56,7 @@ class KinematicEvaluatorNode : public rclcpp::Node * @brief publish the given metric statistic */ DiagnosticStatus generateDiagnosticStatus( - const Metric & metric, const Stat & metric_stat) const; + const Metric & metric, const Accumulator & metric_stat) const; private: geometry_msgs::msg::Pose getCurrentEgoPose() const; @@ -74,8 +75,8 @@ class KinematicEvaluatorNode : public rclcpp::Node // Metrics std::vector metrics_; std::deque stamps_; - std::array>, static_cast(Metric::SIZE)> metric_stats_; - std::unordered_map> metrics_dict_; + std::array>, static_cast(Metric::SIZE)> metric_stats_; + std::unordered_map> metrics_dict_; }; } // namespace kinematic_diagnostics diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/kinematic_metrics.hpp b/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/kinematic_metrics.hpp index d20bf079a363a..e7d18910e7c39 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/kinematic_metrics.hpp +++ b/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics/kinematic_metrics.hpp @@ -15,7 +15,7 @@ #ifndef KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_ #define KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_ -#include "kinematic_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include @@ -23,6 +23,7 @@ namespace kinematic_diagnostics { namespace metrics { +using autoware::universe_utils::Accumulator; using nav_msgs::msg::Odometry; /** @@ -31,7 +32,7 @@ using nav_msgs::msg::Odometry; * @param [in] stat_prev input trajectory * @return calculated statistics */ -Stat updateVelocityStats(const double & value, const Stat stat_prev); +Accumulator updateVelocityStats(const double & value, const Accumulator stat_prev); } // namespace metrics } // namespace kinematic_diagnostics diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics_calculator.hpp b/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics_calculator.hpp index 67f152e30c9eb..372d4a34af62c 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics_calculator.hpp +++ b/evaluator/kinematic_evaluator/include/kinematic_evaluator/metrics_calculator.hpp @@ -15,15 +15,16 @@ #ifndef KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_ #define KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_ +#include "autoware/universe_utils/math/accumulator.hpp" #include "kinematic_evaluator/metrics/metric.hpp" #include "kinematic_evaluator/parameters.hpp" -#include "kinematic_evaluator/stat.hpp" #include "geometry_msgs/msg/pose.hpp" #include namespace kinematic_diagnostics { +using autoware::universe_utils::Accumulator; using nav_msgs::msg::Odometry; class MetricsCalculator @@ -39,7 +40,7 @@ class MetricsCalculator * @param [in] odom Odometry * @return string describing the requested metric */ - Stat calculate(const Metric metric, const Odometry & odom) const; + Accumulator calculate(const Metric metric, const Odometry & odom) const; /** * @brief update Metrics @@ -47,8 +48,8 @@ class MetricsCalculator * @param [in] odom Odometry * @return string describing the requested metric */ - Stat updateStat( - const Metric metric, const Odometry & odom, const Stat stat_prev) const; + Accumulator updateStat( + const Metric metric, const Odometry & odom, const Accumulator stat_prev) const; }; // class MetricsCalculator } // namespace kinematic_diagnostics diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/stat.hpp b/evaluator/kinematic_evaluator/include/kinematic_evaluator/stat.hpp deleted file mode 100644 index 096cb90b3dcf4..0000000000000 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/stat.hpp +++ /dev/null @@ -1,93 +0,0 @@ -// Copyright 2021 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 - -#ifndef KINEMATIC_EVALUATOR__STAT_HPP_ -#define KINEMATIC_EVALUATOR__STAT_HPP_ - -namespace kinematic_diagnostics -{ -/** - * @brief class to incrementally build statistics - * @typedef T type of the values (default to double) - */ -template -class Stat -{ -public: - /** - * @brief add a value - * @param value value to add - */ - void add(const T & value) - { - if (value < min_) { - min_ = value; - } - if (value > max_) { - max_ = value; - } - ++count_; - mean_ = mean_ + (value - mean_) / count_; - } - - /** - * @brief get the mean value - */ - long double mean() const { return mean_; } - - /** - * @brief get the minimum value - */ - T min() const { return min_; } - - /** - * @brief get the maximum value - */ - T max() const { return max_; } - - /** - * @brief get the number of values used to build this statistic - */ - unsigned int count() const { return count_; } - - template - friend std::ostream & operator<<(std::ostream & os, const Stat & stat); - -private: - T min_ = std::numeric_limits::max(); - T max_ = std::numeric_limits::min(); - long double mean_ = 0.0; - unsigned int count_ = 0; -}; - -/** - * @brief overload << operator for easy print to output stream - */ -template -std::ostream & operator<<(std::ostream & os, const Stat & stat) -{ - if (stat.count() == 0) { - os << "None None None"; - } else { - os << stat.min() << " " << stat.max() << " " << stat.mean(); - } - return os; -} - -} // namespace kinematic_diagnostics - -#endif // KINEMATIC_EVALUATOR__STAT_HPP_ diff --git a/evaluator/kinematic_evaluator/src/kinematic_evaluator_node.cpp b/evaluator/kinematic_evaluator/src/kinematic_evaluator_node.cpp index 57631e5f861df..d34f9deb7f1ba 100644 --- a/evaluator/kinematic_evaluator/src/kinematic_evaluator_node.cpp +++ b/evaluator/kinematic_evaluator/src/kinematic_evaluator_node.cpp @@ -46,7 +46,7 @@ KinematicEvaluatorNode::KinematicEvaluatorNode(const rclcpp::NodeOptions & node_ for (const std::string & selected_metric : declare_parameter>("selected_metrics")) { Metric metric = str_to_metric.at(selected_metric); - metrics_dict_[metric] = Stat(); + metrics_dict_[metric] = Accumulator(); metrics_.push_back(metric); } } @@ -83,7 +83,7 @@ KinematicEvaluatorNode::~KinematicEvaluatorNode() } DiagnosticStatus KinematicEvaluatorNode::generateDiagnosticStatus( - const Metric & metric, const Stat & metric_stat) const + const Metric & metric, const Accumulator & metric_stat) const { DiagnosticStatus status; status.level = status.OK; diff --git a/evaluator/kinematic_evaluator/src/metrics/kinematic_metrics.cpp b/evaluator/kinematic_evaluator/src/metrics/kinematic_metrics.cpp index 2bb0dad86bf71..d410863a05010 100644 --- a/evaluator/kinematic_evaluator/src/metrics/kinematic_metrics.cpp +++ b/evaluator/kinematic_evaluator/src/metrics/kinematic_metrics.cpp @@ -19,9 +19,9 @@ namespace kinematic_diagnostics namespace metrics { -Stat updateVelocityStats(const double & value, const Stat stat_prev) +Accumulator updateVelocityStats(const double & value, const Accumulator stat_prev) { - Stat stat(stat_prev); + Accumulator stat(stat_prev); stat.add(value); return stat; } diff --git a/evaluator/kinematic_evaluator/src/metrics_calculator.cpp b/evaluator/kinematic_evaluator/src/metrics_calculator.cpp index af1e1114b9c43..8b0f581817b38 100644 --- a/evaluator/kinematic_evaluator/src/metrics_calculator.cpp +++ b/evaluator/kinematic_evaluator/src/metrics_calculator.cpp @@ -18,8 +18,8 @@ namespace kinematic_diagnostics { -Stat MetricsCalculator::updateStat( - const Metric metric, const Odometry & odom, const Stat stat_prev) const +Accumulator MetricsCalculator::updateStat( + const Metric metric, const Odometry & odom, const Accumulator stat_prev) const { switch (metric) { case Metric::velocity_stats: diff --git a/evaluator/localization_evaluator/include/localization_evaluator/localization_evaluator_node.hpp b/evaluator/localization_evaluator/include/localization_evaluator/localization_evaluator_node.hpp index 8c93ddd5fa0fc..feb61dd3cacbe 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/localization_evaluator_node.hpp +++ b/evaluator/localization_evaluator/include/localization_evaluator/localization_evaluator_node.hpp @@ -15,8 +15,8 @@ #ifndef LOCALIZATION_EVALUATOR__LOCALIZATION_EVALUATOR_NODE_HPP_ #define LOCALIZATION_EVALUATOR__LOCALIZATION_EVALUATOR_NODE_HPP_ +#include "autoware/universe_utils/math/accumulator.hpp" #include "localization_evaluator/metrics_calculator.hpp" -#include "localization_evaluator/stat.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -38,6 +38,7 @@ namespace localization_diagnostics { +using autoware::universe_utils::Accumulator; using diagnostic_msgs::msg::DiagnosticArray; using diagnostic_msgs::msg::DiagnosticStatus; using geometry_msgs::msg::PoseWithCovarianceStamped; @@ -70,7 +71,7 @@ class LocalizationEvaluatorNode : public rclcpp::Node * @brief publish the given metric statistic */ DiagnosticStatus generateDiagnosticStatus( - const Metric & metric, const Stat & metric_stat) const; + const Metric & metric, const Accumulator & metric_stat) const; private: // ROS @@ -93,8 +94,8 @@ class LocalizationEvaluatorNode : public rclcpp::Node // Metrics std::vector metrics_; std::deque stamps_; - std::array>, static_cast(Metric::SIZE)> metric_stats_; - std::unordered_map> metrics_dict_; + std::array>, static_cast(Metric::SIZE)> metric_stats_; + std::unordered_map> metrics_dict_; }; } // namespace localization_diagnostics diff --git a/evaluator/localization_evaluator/include/localization_evaluator/metrics/localization_metrics.hpp b/evaluator/localization_evaluator/include/localization_evaluator/metrics/localization_metrics.hpp index c973d285fd503..82119efca6082 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/metrics/localization_metrics.hpp +++ b/evaluator/localization_evaluator/include/localization_evaluator/metrics/localization_metrics.hpp @@ -15,12 +15,13 @@ #ifndef LOCALIZATION_EVALUATOR__METRICS__LOCALIZATION_METRICS_HPP_ #define LOCALIZATION_EVALUATOR__METRICS__LOCALIZATION_METRICS_HPP_ -#include "localization_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include namespace localization_diagnostics { +using autoware::universe_utils::Accumulator; namespace metrics { /** @@ -30,8 +31,8 @@ namespace metrics * @param [in] lateral_ref reference lateral position * @return calculated statistics */ -Stat updateLateralStats( - const Stat stat_prev, const double & lateral_pos, const double & lateral_ref); +Accumulator updateLateralStats( + const Accumulator stat_prev, const double & lateral_pos, const double & lateral_ref); /** * @brief calculate absolute localization error @@ -40,8 +41,8 @@ Stat updateLateralStats( * @param [in] pos_ref reference position of the vehicle * @return calculated statistics */ -Stat updateAbsoluteStats( - const Stat stat_prev, const geometry_msgs::msg::Point & pos, +Accumulator updateAbsoluteStats( + const Accumulator stat_prev, const geometry_msgs::msg::Point & pos, const geometry_msgs::msg::Point & pos_ref); } // namespace metrics diff --git a/evaluator/localization_evaluator/include/localization_evaluator/metrics_calculator.hpp b/evaluator/localization_evaluator/include/localization_evaluator/metrics_calculator.hpp index 88f8ea85d4267..310d1b25e92f1 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/metrics_calculator.hpp +++ b/evaluator/localization_evaluator/include/localization_evaluator/metrics_calculator.hpp @@ -15,15 +15,16 @@ #ifndef LOCALIZATION_EVALUATOR__METRICS_CALCULATOR_HPP_ #define LOCALIZATION_EVALUATOR__METRICS_CALCULATOR_HPP_ +#include "autoware/universe_utils/math/accumulator.hpp" #include "localization_evaluator/metrics/metric.hpp" #include "localization_evaluator/parameters.hpp" -#include "localization_evaluator/stat.hpp" #include "geometry_msgs/msg/pose.hpp" #include namespace localization_diagnostics { +using autoware::universe_utils::Accumulator; class MetricsCalculator { public: @@ -38,8 +39,8 @@ class MetricsCalculator * @param [in] pos_ref reference position * @return string describing the requested metric */ - Stat updateStat( - const Stat stat_prev, const Metric metric, const geometry_msgs::msg::Point & pos, + Accumulator updateStat( + const Accumulator stat_prev, const Metric metric, const geometry_msgs::msg::Point & pos, const geometry_msgs::msg::Point & pos_ref) const; }; // class MetricsCalculator diff --git a/evaluator/localization_evaluator/include/localization_evaluator/stat.hpp b/evaluator/localization_evaluator/include/localization_evaluator/stat.hpp deleted file mode 100644 index fbea5b61813fb..0000000000000 --- a/evaluator/localization_evaluator/include/localization_evaluator/stat.hpp +++ /dev/null @@ -1,93 +0,0 @@ -// Copyright 2021 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 - -#ifndef LOCALIZATION_EVALUATOR__STAT_HPP_ -#define LOCALIZATION_EVALUATOR__STAT_HPP_ - -namespace localization_diagnostics -{ -/** - * @brief class to incrementally build statistics - * @typedef T type of the values (default to double) - */ -template -class Stat -{ -public: - /** - * @brief add a value - * @param value value to add - */ - void add(const T & value) - { - if (value < min_) { - min_ = value; - } - if (value > max_) { - max_ = value; - } - ++count_; - mean_ = mean_ + (value - mean_) / count_; - } - - /** - * @brief get the mean value - */ - long double mean() const { return mean_; } - - /** - * @brief get the minimum value - */ - T min() const { return min_; } - - /** - * @brief get the maximum value - */ - T max() const { return max_; } - - /** - * @brief get the number of values used to build this statistic - */ - unsigned int count() const { return count_; } - - template - friend std::ostream & operator<<(std::ostream & os, const Stat & stat); - -private: - T min_ = std::numeric_limits::max(); - T max_ = std::numeric_limits::min(); - long double mean_ = 0.0; - unsigned int count_ = 0; -}; - -/** - * @brief overload << operator for easy print to output stream - */ -template -std::ostream & operator<<(std::ostream & os, const Stat & stat) -{ - if (stat.count() == 0) { - os << "None None None"; - } else { - os << stat.min() << " " << stat.max() << " " << stat.mean(); - } - return os; -} - -} // namespace localization_diagnostics - -#endif // LOCALIZATION_EVALUATOR__STAT_HPP_ diff --git a/evaluator/localization_evaluator/src/localization_evaluator_node.cpp b/evaluator/localization_evaluator/src/localization_evaluator_node.cpp index db0c04a698725..8a9352d2a73e8 100644 --- a/evaluator/localization_evaluator/src/localization_evaluator_node.cpp +++ b/evaluator/localization_evaluator/src/localization_evaluator_node.cpp @@ -49,7 +49,7 @@ LocalizationEvaluatorNode::LocalizationEvaluatorNode(const rclcpp::NodeOptions & for (const std::string & selected_metric : declare_parameter>("selected_metrics")) { Metric metric = str_to_metric.at(selected_metric); - metrics_dict_[metric] = Stat(); + metrics_dict_[metric] = Accumulator(); metrics_.push_back(metric); } } @@ -86,7 +86,7 @@ LocalizationEvaluatorNode::~LocalizationEvaluatorNode() } DiagnosticStatus LocalizationEvaluatorNode::generateDiagnosticStatus( - const Metric & metric, const Stat & metric_stat) const + const Metric & metric, const Accumulator & metric_stat) const { DiagnosticStatus status; status.level = status.OK; diff --git a/evaluator/localization_evaluator/src/metrics/localization_metrics.cpp b/evaluator/localization_evaluator/src/metrics/localization_metrics.cpp index fab3377913bd4..97fd8e326cca7 100644 --- a/evaluator/localization_evaluator/src/metrics/localization_metrics.cpp +++ b/evaluator/localization_evaluator/src/metrics/localization_metrics.cpp @@ -21,19 +21,19 @@ namespace localization_diagnostics namespace metrics { -Stat updateLateralStats( - const Stat stat_prev, const double & lateral_pos, const double & lateral_ref) +Accumulator updateLateralStats( + const Accumulator stat_prev, const double & lateral_pos, const double & lateral_ref) { - Stat stat(stat_prev); + Accumulator stat(stat_prev); stat.add(std::abs(lateral_ref - lateral_pos)); return stat; } -Stat updateAbsoluteStats( - const Stat stat_prev, const geometry_msgs::msg::Point & pos, +Accumulator updateAbsoluteStats( + const Accumulator stat_prev, const geometry_msgs::msg::Point & pos, const geometry_msgs::msg::Point & pos_ref) { - Stat stat(stat_prev); + Accumulator stat(stat_prev); double dist = std::sqrt( (pos_ref.x - pos.x) * (pos_ref.x - pos.x) + (pos_ref.y - pos.y) * (pos_ref.y - pos.y) + (pos_ref.z - pos.z) * (pos_ref.z - pos.z)); diff --git a/evaluator/localization_evaluator/src/metrics_calculator.cpp b/evaluator/localization_evaluator/src/metrics_calculator.cpp index 72184937e846b..864fb4a5ddbd2 100644 --- a/evaluator/localization_evaluator/src/metrics_calculator.cpp +++ b/evaluator/localization_evaluator/src/metrics_calculator.cpp @@ -18,8 +18,8 @@ namespace localization_diagnostics { -Stat MetricsCalculator::updateStat( - const Stat stat_prev, const Metric metric, const geometry_msgs::msg::Point & pos, +Accumulator MetricsCalculator::updateStat( + const Accumulator stat_prev, const Metric metric, const geometry_msgs::msg::Point & pos, const geometry_msgs::msg::Point & pos_ref) const { if ( diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp index 010f1497da3da..c111a725a2ea0 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp @@ -16,7 +16,6 @@ #define PERCEPTION_ONLINE_EVALUATOR__METRICS__DETECTION_COUNT_HPP_ #include "perception_online_evaluator/parameters.hpp" -#include "perception_online_evaluator/stat.hpp" #include "tf2_ros/buffer.h" #include diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/deviation_metrics.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/deviation_metrics.hpp index d67413c174c41..0f3379b3f055e 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/deviation_metrics.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/deviation_metrics.hpp @@ -15,8 +15,6 @@ #ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ #define PERCEPTION_ONLINE_EVALUATOR__METRICS__DEVIATION_METRICS_HPP_ -#include "perception_online_evaluator/stat.hpp" - #include #include diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp index eaa07f2317940..4caf932919e61 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/metric.hpp @@ -15,7 +15,7 @@ #ifndef PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_ #define PERCEPTION_ONLINE_EVALUATOR__METRICS__METRIC_HPP_ -#include "perception_online_evaluator/stat.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include #include @@ -39,14 +39,15 @@ enum class Metric { // Each metric has a different return type. (statistic or just a one value etc). // To handle them all in the MetricsCalculator::calculate function, define MetricsMap as a variant -using MetricStatMap = std::unordered_map>; +using autoware::universe_utils::Accumulator; +using MetricStatMap = std::unordered_map>; using MetricValueMap = std::unordered_map; using MetricsMap = std::variant; struct PredictedPathDeviationMetrics { - Stat mean; - Stat variance; + Accumulator mean; + Accumulator variance; }; static const std::unordered_map str_to_metric = { diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp index a9b1388281ce8..c17051d2a30a7 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics_calculator.hpp @@ -19,7 +19,6 @@ #include "perception_online_evaluator/metrics/deviation_metrics.hpp" #include "perception_online_evaluator/metrics/metric.hpp" #include "perception_online_evaluator/parameters.hpp" -#include "perception_online_evaluator/stat.hpp" #include "perception_online_evaluator/utils/objects_filtering.hpp" #include "tf2_ros/buffer.h" diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp index 1bc427e667a2a..ea560a48f928b 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp @@ -15,9 +15,9 @@ #ifndef PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_ #define PERCEPTION_ONLINE_EVALUATOR__PERCEPTION_ONLINE_EVALUATOR_NODE_HPP_ +#include "autoware/universe_utils/math/accumulator.hpp" #include "perception_online_evaluator/metrics_calculator.hpp" #include "perception_online_evaluator/parameters.hpp" -#include "perception_online_evaluator/stat.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -35,6 +35,7 @@ namespace perception_diagnostics { +using autoware::universe_utils::Accumulator; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; using diagnostic_msgs::msg::DiagnosticArray; @@ -60,7 +61,7 @@ class PerceptionOnlineEvaluatorNode : public rclcpp::Node void onObjects(const PredictedObjects::ConstSharedPtr objects_msg); DiagnosticStatus generateDiagnosticStatus( - const std::string metric, const Stat & metric_stat) const; + const std::string metric, const Accumulator & metric_stat) const; DiagnosticStatus generateDiagnosticStatus( const std::string & metric, const double metric_value) const; diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/stat.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/stat.hpp deleted file mode 100644 index 63494f90d02ee..0000000000000 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/stat.hpp +++ /dev/null @@ -1,93 +0,0 @@ -// 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 - -#ifndef PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_ -#define PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_ - -namespace perception_diagnostics -{ -/** - * @brief class to incrementally build statistics - * @typedef T type of the values (default to double) - */ -template -class Stat -{ -public: - /** - * @brief add a value - * @param value value to add - */ - void add(const T & value) - { - if (value < min_) { - min_ = value; - } - if (value > max_) { - max_ = value; - } - ++count_; - mean_ = mean_ + (value - mean_) / count_; - } - - /** - * @brief get the mean value - */ - long double mean() const { return mean_; } - - /** - * @brief get the minimum value - */ - T min() const { return min_; } - - /** - * @brief get the maximum value - */ - T max() const { return max_; } - - /** - * @brief get the number of values used to build this statistic - */ - unsigned int count() const { return count_; } - - template - friend std::ostream & operator<<(std::ostream & os, const Stat & stat); - -private: - T min_ = std::numeric_limits::max(); - T max_ = std::numeric_limits::min(); - long double mean_ = 0.0; - unsigned int count_ = 0; -}; - -/** - * @brief overload << operator for easy print to output stream - */ -template -std::ostream & operator<<(std::ostream & os, const Stat & stat) -{ - if (stat.count() == 0) { - os << "None None None"; - } else { - os << stat.min() << " " << stat.max() << " " << stat.mean(); - } - return os; -} - -} // namespace perception_diagnostics - -#endif // PERCEPTION_ONLINE_EVALUATOR__STAT_HPP_ diff --git a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp index fea4316fa6820..0ced0b9d6c8a8 100644 --- a/evaluator/perception_online_evaluator/src/metrics_calculator.cpp +++ b/evaluator/perception_online_evaluator/src/metrics_calculator.cpp @@ -235,7 +235,7 @@ MetricStatMap MetricsCalculator::calcLateralDeviationMetrics( !parameters_->object_parameters.at(label).check_lateral_deviation) { continue; } - Stat stat{}; + Accumulator stat{}; const auto stamp = rclcpp::Time(objects.header.stamp); for (const auto & object : objects.objects) { const auto uuid = autoware::universe_utils::toHexString(object.object_id); @@ -264,7 +264,7 @@ MetricStatMap MetricsCalculator::calcYawDeviationMetrics( !parameters_->object_parameters.at(label).check_yaw_deviation) { continue; } - Stat stat{}; + Accumulator stat{}; const auto stamp = rclcpp::Time(objects.header.stamp); for (const auto & object : objects.objects) { const auto uuid = autoware::universe_utils::toHexString(object.object_id); @@ -420,7 +420,7 @@ MetricStatMap MetricsCalculator::calcYawRateMetrics(const ClassObjectsMap & clas MetricStatMap metric_stat_map{}; for (const auto & [label, objects] : class_objects_map) { - Stat stat{}; + Accumulator stat{}; const auto stamp = rclcpp::Time(objects.header.stamp); for (const auto & object : objects.objects) { diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index a577fd359563c..abbdbd382498a 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -99,7 +99,7 @@ void PerceptionOnlineEvaluatorNode::publishMetrics() } DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus( - const std::string metric, const Stat & metric_stat) const + const std::string metric, const Accumulator & metric_stat) const { DiagnosticStatus status; From 64e5a69031f53ec2d0635618f06ab57445d8eb94 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Wed, 27 Nov 2024 14:21:41 +0900 Subject: [PATCH 134/273] test(bpp_common): add unit test for utils (#9469) * add easy unit test Signed-off-by: Go Sakayori * fix clang tidy warning and add unit test Signed-off-by: Go Sakayori * add more unit test Signed-off-by: Go Sakayori * add docstring Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../utils/utils.hpp | 116 +++++- .../src/utils/utils.cpp | 17 +- .../test/test_utils.cpp | 347 +++++++++++++++++- 3 files changed, 461 insertions(+), 19 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp index d6d37c3f581e4..7162f49b450e8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/utils.hpp @@ -137,9 +137,21 @@ double l2Norm(const Vector3 vector); double getDistanceToEndOfLane(const Pose & current_pose, const lanelet::ConstLanelets & lanelets); +/** + * @brief Calculates the distance to the next intersection. + * @param current_pose Ego pose. + * @param lanelets Lanelets to check. + * @return Distance. + */ double getDistanceToNextIntersection( const Pose & current_pose, const lanelet::ConstLanelets & lanelets); +/** + * @brief Calculates the distance to the next crosswalk. + * @param current_pose Ego pose. + * @param lanelets Lanelets to check. + * @return Distance. + */ double getDistanceToCrosswalk( const Pose & current_pose, const lanelet::ConstLanelets & lanelets, const lanelet::routing::RoutingGraphContainer & overall_graphs); @@ -236,6 +248,15 @@ bool set_goal( */ const Pose refineGoal(const Pose & goal, const lanelet::ConstLanelet & goal_lanelet); +/** + * @brief Recreate the path with a given goal pose. + * @param search_radius_range Searching radius. + * @param search_rad_range Searching angle. + * @param input Input path. + * @param goal Goal pose. + * @param goal_lane_id Lane ID of goal lanelet. + * @return Recreated path + */ PathWithLaneId refinePathForGoal( const double search_radius_range, const double search_rad_range, const PathWithLaneId & input, const Pose & goal, const int64_t goal_lane_id); @@ -243,8 +264,22 @@ PathWithLaneId refinePathForGoal( bool isAllowedGoalModification(const std::shared_ptr & route_handler); bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_handler); +/** + * @brief Checks if the given pose is inside the given lanes. + * @param pose Ego pose. + * @param lanes Lanelets to check. + * @return True if the ego pose is inside the lanes. + */ bool isInLanelets(const Pose & pose, const lanelet::ConstLanelets & lanes); +/** + * @brief Checks if the given pose is inside the given lane within certain yaw difference. + * @param current_pose Ego pose. + * @param lanelet Lanelet to check. + * @param yaw_threshold Yaw angle difference threshold. + * @param radius Search radius + * @return True if the ego pose is inside the lane. + */ bool isInLaneletWithYawThreshold( const Pose & current_pose, const lanelet::ConstLanelet & lanelet, const double yaw_threshold, const double radius = 0.0); @@ -254,6 +289,14 @@ bool isEgoOutOfRoute( const std::optional & modified_goal, const std::shared_ptr & route_handler); +/** + * @brief Checks if the given pose is inside the original lane. + * @param current_lanes Original lanes. + * @param current_pose Ego pose. + * @param common_param Parameters used for behavior path planner. + * @param outer_margin Allowed margin. + * @return True if the ego pose is inside the original lane. + */ bool isEgoWithinOriginalLane( const lanelet::ConstLanelets & current_lanes, const Pose & current_pose, const BehaviorPathPlannerParameters & common_param, const double outer_margin = 0.0); @@ -268,18 +311,48 @@ bool isEgoWithinOriginalLane( std::shared_ptr generateCenterLinePath( const std::shared_ptr & planner_data); +/** + * @brief Inserts a stop point with given length + * @param length Distance to insert stop point. + * @param path Original path. + * @return Inserted stop point. + */ PathPointWithLaneId insertStopPoint(const double length, PathWithLaneId & path); +/** + * @brief Calculates distance to lane boundary. + * @param lanelet Target lanelet. + * @param position Ego position. + * @param left_side Whether to check left side boundary. + * @return Distance to boundary. + */ double getSignedDistanceFromLaneBoundary( const lanelet::ConstLanelet & lanelet, const Point & position, const bool left_side); + double getSignedDistanceFromBoundary( const lanelet::ConstLanelets & lanelets, const Pose & pose, const bool left_side); + +/** + * @brief Calculates distance to lane boundary. + * @param lanelet Target lanelet. + * @param vehicle_width Ego vehicle width. + * @param base_link2front Ego vehicle distance from base link to front. + * @param base_link2rear Ego vehicle distance from base link to rear. + * @param vehicle_pose Ego vehicle pose. + * @param left_side Whether to check left side boundary. + * @return Distance to boundary. + */ std::optional getSignedDistanceFromBoundary( const lanelet::ConstLanelets & lanelets, const double vehicle_width, const double base_link2front, const double base_link2rear, const Pose & vehicle_pose, const bool left_side); // misc +/** + * @brief Convert lanelet to 2D polygon. + * @param lanelet Target lanelet. + * @return Polygon + */ Polygon2d toPolygon2d(const lanelet::ConstLanelet & lanelet); Polygon2d toPolygon2d(const lanelet::BasicPolygon2d & polygon); @@ -316,10 +389,27 @@ lanelet::ConstLanelets extendPrevLane( lanelet::ConstLanelets extendLanes( const std::shared_ptr route_handler, const lanelet::ConstLanelets & lanes); +/** + * @brief Retrieves sequences of preceding lanelets from the target lanes. + * @param route_handler Reference to the route handler. + * @param target_lanes The set of target lanelets. + * @param current_pose The current pose of ego vehicle. + * @param backward_length The backward search length [m]. + * @return A vector of lanelet sequences that precede the target lanes + */ std::vector getPrecedingLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const double backward_length); +/** + * @brief Retrieves all preceding lanelets as a flat list. + * @param route_handler Reference to the route handler. + * @param target_lanes The set of target lanelets. + * @param current_pose The current pose of ego vehicle. + * @param backward_length The backward search length [m]. + * @return Preceding lanelets within the specified backward length. + */ + lanelet::ConstLanelets getBackwardLanelets( const RouteHandler & route_handler, const lanelet::ConstLanelets & target_lanes, const Pose & current_pose, const double backward_length); @@ -335,17 +425,41 @@ lanelet::ConstLanelets getExtendedCurrentLanesFromPath( const PathWithLaneId & path, const std::shared_ptr & planner_data, const double backward_length, const double forward_length, const bool forward_only_in_route); +/** + * @brief Calculates the sequence of lanelets around a given pose within a specified range. + * @param route_handler A shared pointer to the RouteHandler for accessing route and lanelet + * information. + * @param pose The reference pose to locate the lanelets around. + * @param forward_length The length of the route to extend forward from the reference pose. + * @param backward_length The length of the route to extend backward from the reference pose. + * @param dist_threshold The maximum allowable distance to consider a lanelet as closest. + * @param yaw_threshold The maximum allowable yaw difference (in radians) for lanelet matching. + * @return A sequence of lanelets around the given pose. + */ lanelet::ConstLanelets calcLaneAroundPose( - const std::shared_ptr route_handler, const geometry_msgs::msg::Pose & pose, + const std::shared_ptr & route_handler, const geometry_msgs::msg::Pose & pose, const double forward_length, const double backward_length, const double dist_threshold = std::numeric_limits::max(), const double yaw_threshold = std::numeric_limits::max()); +/** + * @brief Checks whether the relative angles between consecutive triplets of points in a path remain + * within a specified threshold. + * @param path Input path. + * @param angle_threshold The maximum allowable angle in radians. + * @return True if all relative angles are within the threshold or the path has fewer than three + * points. + */ bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold); lanelet::ConstLanelets getLaneletsFromPath( const PathWithLaneId & path, const std::shared_ptr & route_handler); +/** + * @brief Converts camel case string to snake case string. + * @param input_str Input string. + * @return String + */ std::string convertToSnakeCase(const std::string & input_str); std::optional getPolygonByPoint( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp index a546c0026d4d6..a224ef16bc0d9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp @@ -380,9 +380,8 @@ PathWithLaneId refinePathForGoal( search_radius_range, search_rad_range, filtered_path, goal, goal_lane_id, &path_with_goal)) { return path_with_goal; - } else { - return filtered_path; } + return filtered_path; } bool isInLanelets(const Pose & pose, const lanelet::ConstLanelets & lanes) @@ -441,9 +440,8 @@ bool isEgoOutOfRoute( RCLCPP_WARN_STREAM( rclcpp::get_logger("behavior_path_planner").get_child("util"), "ego pose is beyond goal"); return true; - } else { - return false; } + return false; } // If ego vehicle is out of the closest lanelet, return true @@ -466,11 +464,7 @@ bool isEgoOutOfRoute( return false; }); - if (!is_in_shoulder_lane && !is_in_road_lane) { - return true; - } - - return false; + return !is_in_shoulder_lane && !is_in_road_lane; } bool isEgoWithinOriginalLane( @@ -1359,8 +1353,9 @@ lanelet::ConstLanelets getBackwardLanelets( } lanelet::ConstLanelets calcLaneAroundPose( - const std::shared_ptr route_handler, const Pose & pose, const double forward_length, - const double backward_length, const double dist_threshold, const double yaw_threshold) + const std::shared_ptr & route_handler, const Pose & pose, + const double forward_length, const double backward_length, const double dist_threshold, + const double yaw_threshold) { lanelet::ConstLanelet current_lane; if (!route_handler->getClosestLaneletWithConstrainsWithinRoute( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp index 4326cfdb8e6be..2234574fce83e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp @@ -15,8 +15,14 @@ #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include +#include #include +#include + +#include +#include +#include using autoware::universe_utils::Point2d; using autoware_perception_msgs::msg::PredictedObject; @@ -25,11 +31,55 @@ using autoware_planning_msgs::msg::Trajectory; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; using ObjectClassification = autoware_perception_msgs::msg::ObjectClassification; +using autoware::behavior_path_planner::PlannerData; +using autoware_planning_msgs::msg::LaneletRoute; using autoware::test_utils::createPose; using autoware::test_utils::generateTrajectory; -TEST(BehaviorPathPlanningUtilTest, l2Norm) +class BehaviorPathPlanningUtilTest : public ::testing::Test +{ +protected: + void SetUp() override + { + planner_data_ = std::make_shared(); + const auto test_data_file = + ament_index_cpp::get_package_share_directory("autoware_behavior_path_planner_common") + + "/test_data/test_traffic_light.yaml"; + YAML::Node config = YAML::LoadFile(test_data_file); + + set_current_pose(config); + set_route_handler(config); + } + + void set_current_pose(YAML::Node config) + { + const auto self_odometry = + autoware::test_utils::parse(config["self_odometry"]); + planner_data_->self_odometry = std::make_shared(self_odometry); + } + + void set_route_handler(YAML::Node config) + { + const auto route = autoware::test_utils::parse(config["route"]); + const auto intersection_map = + autoware::test_utils::make_map_bin_msg(autoware::test_utils::get_absolute_path_to_lanelet_map( + "autoware_test_utils", "intersection/lanelet2_map.osm")); + planner_data_->route_handler->setMap(intersection_map); + planner_data_->route_handler->setRoute(route); + + for (const auto & segment : route.segments) { + current_lanelets.push_back( + planner_data_->route_handler->getLaneletsFromId(segment.preferred_primitive.id)); + } + } + + std::shared_ptr planner_data_; + lanelet::ConstLanelets current_lanelets; + const double epsilon = 1e-06; +}; + +TEST_F(BehaviorPathPlanningUtilTest, l2Norm) { using autoware::behavior_path_planner::utils::l2Norm; @@ -42,7 +92,7 @@ TEST(BehaviorPathPlanningUtilTest, l2Norm) EXPECT_DOUBLE_EQ(norm, 3.0); } -TEST(BehaviorPathPlanningUtilTest, checkCollisionBetweenPathFootprintsAndObjects) +TEST_F(BehaviorPathPlanningUtilTest, checkCollisionBetweenPathFootprintsAndObjects) { using autoware::behavior_path_planner::utils::checkCollisionBetweenPathFootprintsAndObjects; @@ -75,7 +125,7 @@ TEST(BehaviorPathPlanningUtilTest, checkCollisionBetweenPathFootprintsAndObjects checkCollisionBetweenPathFootprintsAndObjects(base_footprint, ego_path, objs, margin)); } -TEST(BehaviorPathPlanningUtilTest, checkCollisionBetweenFootprintAndObjects) +TEST_F(BehaviorPathPlanningUtilTest, checkCollisionBetweenFootprintAndObjects) { using autoware::behavior_path_planner::utils::checkCollisionBetweenFootprintAndObjects; @@ -105,7 +155,7 @@ TEST(BehaviorPathPlanningUtilTest, checkCollisionBetweenFootprintAndObjects) EXPECT_TRUE(checkCollisionBetweenFootprintAndObjects(base_footprint, ego_pose, objs, margin)); } -TEST(BehaviorPathPlanningUtilTest, calcLateralDistanceFromEgoToObject) +TEST_F(BehaviorPathPlanningUtilTest, calcLateralDistanceFromEgoToObject) { using autoware::behavior_path_planner::utils::calcLateralDistanceFromEgoToObject; @@ -130,7 +180,7 @@ TEST(BehaviorPathPlanningUtilTest, calcLateralDistanceFromEgoToObject) EXPECT_DOUBLE_EQ(calcLateralDistanceFromEgoToObject(ego_pose, vehicle_width, obj), 3.0); } -TEST(BehaviorPathPlanningUtilTest, calc_longitudinal_distance_from_ego_to_object) +TEST_F(BehaviorPathPlanningUtilTest, calc_longitudinal_distance_from_ego_to_object) { using autoware::behavior_path_planner::utils::calc_longitudinal_distance_from_ego_to_object; @@ -164,7 +214,7 @@ TEST(BehaviorPathPlanningUtilTest, calc_longitudinal_distance_from_ego_to_object 2.0); } -TEST(BehaviorPathPlanningUtilTest, calcLongitudinalDistanceFromEgoToObjects) +TEST_F(BehaviorPathPlanningUtilTest, calcLongitudinalDistanceFromEgoToObjects) { using autoware::behavior_path_planner::utils::calcLongitudinalDistanceFromEgoToObjects; @@ -198,7 +248,206 @@ TEST(BehaviorPathPlanningUtilTest, calcLongitudinalDistanceFromEgoToObjects) calcLongitudinalDistanceFromEgoToObjects(ego_pose, base_link2front, base_link2rear, objs), 3.0); } -TEST(BehaviorPathPlanningUtilTest, getHighestProbLabel) +TEST_F(BehaviorPathPlanningUtilTest, refineGoal) +{ + using autoware::behavior_path_planner::utils::refineGoal; + + { + const auto goal_lanelet = current_lanelets.front(); + const auto goal_pose = planner_data_->self_odometry->pose.pose; + const auto refined_pose = refineGoal(goal_pose, goal_lanelet); + EXPECT_DOUBLE_EQ(refined_pose.position.x, goal_pose.position.x); + EXPECT_DOUBLE_EQ(refined_pose.position.y, goal_pose.position.y); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, refinePathForGoal) +{ + using autoware::behavior_path_planner::utils::refinePathForGoal; + + auto path = generateTrajectory(10, 1.0, 3.0); + const double search_rad_range = M_PI; + const auto goal_pose = createPose(5.2, 0.0, 0.0, 0.0, 0.0, 0.0); + const int64_t goal_lane_id = 5; + { + const double search_radius_range = 1.0; + const auto refined_path = + refinePathForGoal(search_radius_range, search_rad_range, path, goal_pose, goal_lane_id); + EXPECT_EQ(refined_path.points.size(), 7); + EXPECT_DOUBLE_EQ(refined_path.points.back().point.longitudinal_velocity_mps, 0.0); + EXPECT_DOUBLE_EQ(refined_path.points.back().point.pose.position.x, 5.2); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, isInLanelets) +{ + using autoware::behavior_path_planner::utils::isInLanelets; + using autoware::behavior_path_planner::utils::isInLaneletWithYawThreshold; + + { + const auto pose = createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); + EXPECT_FALSE(isInLanelets(pose, current_lanelets)); + EXPECT_FALSE(isInLaneletWithYawThreshold(pose, current_lanelets.front(), M_PI_2)); + } + { + EXPECT_TRUE(isInLanelets(planner_data_->self_odometry->pose.pose, current_lanelets)); + EXPECT_TRUE(isInLaneletWithYawThreshold( + planner_data_->self_odometry->pose.pose, current_lanelets.front(), M_PI_2)); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, isEgoWithinOriginalLane) +{ + using autoware::behavior_path_planner::utils::isEgoWithinOriginalLane; + BehaviorPathPlannerParameters common_param; + common_param.vehicle_width = 1.0; + common_param.base_link2front = 1.0; + common_param.base_link2rear = 1.0; + + { + const auto pose = createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); + EXPECT_FALSE(isEgoWithinOriginalLane(current_lanelets, pose, common_param)); + } + { + EXPECT_TRUE(isEgoWithinOriginalLane( + current_lanelets, planner_data_->self_odometry->pose.pose, common_param)); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, getDistanceToNextIntersection) +{ + using autoware::behavior_path_planner::utils::getDistanceToNextIntersection; + + const auto current_pose = planner_data_->self_odometry->pose.pose; + { + const lanelet::ConstLanelets empty_lanelets; + EXPECT_DOUBLE_EQ( + getDistanceToNextIntersection(current_pose, empty_lanelets), + std::numeric_limits::infinity()); + } + { + EXPECT_NEAR( + getDistanceToNextIntersection(current_pose, current_lanelets), 117.1599371, epsilon); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, getDistanceToCrosswalk) +{ + using autoware::behavior_path_planner::utils::getDistanceToCrosswalk; + + const auto current_pose = planner_data_->self_odometry->pose.pose; + const auto routing_graph = planner_data_->route_handler->getOverallGraphPtr(); + { + const lanelet::ConstLanelets empty_lanelets; + EXPECT_DOUBLE_EQ( + getDistanceToCrosswalk(current_pose, empty_lanelets, *routing_graph), + std::numeric_limits::infinity()); + } + { + EXPECT_NEAR( + getDistanceToCrosswalk(current_pose, current_lanelets, *routing_graph), 120.4423193, epsilon); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, insertStopPoint) +{ + using autoware::behavior_path_planner::utils::insertStopPoint; + + { + const double length = 100.0; + auto path = generateTrajectory(10, 1.0, 1.0); + EXPECT_DOUBLE_EQ(insertStopPoint(length, path).point.pose.position.x, 0.0); + } + { + const double length = 5.0; + auto path = generateTrajectory(10, 1.0, 1.0); + EXPECT_DOUBLE_EQ(insertStopPoint(length, path).point.pose.position.x, 5.0); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, getSignedDistanceFromBoundary) +{ + using autoware::behavior_path_planner::utils::getSignedDistanceFromBoundary; + + { + lanelet::ConstLanelets empty_lanelets; + EXPECT_DOUBLE_EQ( + getSignedDistanceFromBoundary(empty_lanelets, planner_data_->self_odometry->pose.pose, true), + 0.0); + } + { + EXPECT_NEAR( + getSignedDistanceFromBoundary( + current_lanelets, planner_data_->self_odometry->pose.pose, true), + -1.4952926, epsilon); + EXPECT_NEAR( + getSignedDistanceFromBoundary( + current_lanelets, planner_data_->self_odometry->pose.pose, false), + 1.504715076, epsilon); + } + { + const double vehicle_width = 1.0; + const double base_link2front = 1.0; + const double base_link2rear = 1.0; + + const auto left_distance = getSignedDistanceFromBoundary( + current_lanelets, vehicle_width, base_link2front, base_link2rear, + planner_data_->self_odometry->pose.pose, true); + ASSERT_TRUE(left_distance.has_value()); + EXPECT_NEAR(left_distance.value(), -0.9946984, epsilon); + + const auto right_distance = getSignedDistanceFromBoundary( + current_lanelets, vehicle_width, base_link2front, base_link2rear, + planner_data_->self_odometry->pose.pose, false); + ASSERT_TRUE(right_distance.has_value()); + EXPECT_NEAR(right_distance.value(), 1.0041208, epsilon); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, getArcLengthToTargetLanelet) +{ + using autoware::behavior_path_planner::utils::getArcLengthToTargetLanelet; + { + auto target_lane = current_lanelets.front(); + EXPECT_DOUBLE_EQ( + getArcLengthToTargetLanelet( + current_lanelets, target_lane, planner_data_->self_odometry->pose.pose), + 0.0); + } + { + auto target_lane = current_lanelets.at(1); + EXPECT_NEAR( + getArcLengthToTargetLanelet( + current_lanelets, target_lane, planner_data_->self_odometry->pose.pose), + 86.78265658, epsilon); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, toPolygon2d) +{ + using autoware::behavior_path_planner::utils::toPolygon2d; + + const auto lanelet = current_lanelets.front(); + const auto lanelet_polygon = lanelet.polygon2d().basicPolygon(); + + auto polygon_converted_from_lanelet = toPolygon2d(lanelet); + auto polygon_converted_from_basic_polygon = toPolygon2d(lanelet_polygon); + + EXPECT_EQ( + polygon_converted_from_lanelet.outer().size(), + polygon_converted_from_basic_polygon.outer().size()); + + for (size_t i = 0; i < polygon_converted_from_lanelet.outer().size(); i++) { + EXPECT_DOUBLE_EQ( + polygon_converted_from_lanelet.outer().at(i).x(), + polygon_converted_from_basic_polygon.outer().at(i).x()); + EXPECT_DOUBLE_EQ( + polygon_converted_from_lanelet.outer().at(i).y(), + polygon_converted_from_basic_polygon.outer().at(i).y()); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, getHighestProbLabel) { using autoware::behavior_path_planner::utils::getHighestProbLabel; @@ -217,3 +466,87 @@ TEST(BehaviorPathPlanningUtilTest, getHighestProbLabel) .probability(0.6)); EXPECT_EQ(getHighestProbLabel(obj.classification), ObjectClassification::Type::TRUCK); } + +TEST_F(BehaviorPathPlanningUtilTest, getPrecedingLanelets) +{ + using autoware::behavior_path_planner::utils::getPrecedingLanelets; + const auto & route_handler_ptr = planner_data_->route_handler; + + { + const lanelet::ConstLanelets target_lanes; + EXPECT_TRUE(getPrecedingLanelets( + *route_handler_ptr, target_lanes, planner_data_->self_odometry->pose.pose, 10.0) + .empty()); + } + { + lanelet::ConstLanelets target_lanes; + target_lanes.push_back(route_handler_ptr->getLaneletsFromId(1001)); + EXPECT_TRUE(getPrecedingLanelets( + *route_handler_ptr, target_lanes, planner_data_->self_odometry->pose.pose, 0.0) + .empty()); + } + { + lanelet::ConstLanelets target_lanes; + target_lanes.push_back(route_handler_ptr->getLaneletsFromId(1011)); + target_lanes.push_back(route_handler_ptr->getLaneletsFromId(1101)); + const auto preceding_lanelets = getPrecedingLanelets( + *route_handler_ptr, target_lanes, planner_data_->self_odometry->pose.pose, 10.0); + ASSERT_FALSE(preceding_lanelets.empty()); + EXPECT_EQ(preceding_lanelets.front().data()->id(), 1001); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, getBackwardLanelets) +{ + using autoware::behavior_path_planner::utils::getBackwardLanelets; + + const auto & route_handler_ptr = planner_data_->route_handler; + lanelet::ConstLanelets target_lanes; + target_lanes.push_back(route_handler_ptr->getLaneletsFromId(1011)); + const auto backward_lanelets = getBackwardLanelets( + *route_handler_ptr, target_lanes, planner_data_->self_odometry->pose.pose, 10.0); + ASSERT_FALSE(backward_lanelets.empty()); + EXPECT_EQ(backward_lanelets.front().id(), 1001); +} + +TEST_F(BehaviorPathPlanningUtilTest, calcLaneAroundPose) +{ + using autoware::behavior_path_planner::utils::calcLaneAroundPose; + + { + const auto pose = createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0); + std::shared_ptr route_handler_null = + std::make_shared(); + const auto lane = calcLaneAroundPose(route_handler_null, pose, 10.0, 0.0); + EXPECT_TRUE(lane.empty()); + } + { + const auto lane = calcLaneAroundPose( + planner_data_->route_handler, planner_data_->self_odometry->pose.pose, 10.0, 0.0); + EXPECT_EQ(lane.size(), 1); + EXPECT_EQ(lane.front().id(), 1001); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, checkPathRelativeAngle) +{ + using autoware::behavior_path_planner::utils::checkPathRelativeAngle; + + { + auto path = generateTrajectory(2, 1.0); + EXPECT_TRUE(checkPathRelativeAngle(path, 0.0)); + } + { + auto path = generateTrajectory(10, 1.0); + EXPECT_TRUE(checkPathRelativeAngle(path, M_PI_2)); + } +} + +TEST_F(BehaviorPathPlanningUtilTest, convertToSnakeCase) +{ + using autoware::behavior_path_planner::utils::convertToSnakeCase; + + std::string input_string = "testString"; + auto converted_string = convertToSnakeCase(input_string); + EXPECT_EQ(converted_string, "test_string"); +} From ddff5c2719c8c19b95090b3105de3909b92e1d97 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Wed, 27 Nov 2024 14:49:48 +0900 Subject: [PATCH 135/273] refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files (#9470) * refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files Signed-off-by: Y.Hisaki * Update planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> * fix Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> --- .../behavior_planning.launch.xml | 1 + .../behavior_velocity_planner.param.yaml | 5 -- .../behavior_velocity_planner.launch.xml | 5 +- .../behavior_velocity_planner.schema.json | 32 +--------- .../test/src/test_node_interface.cpp | 42 +++++++------ .../CMakeLists.txt | 4 +- ...ehavior_velocity_planner_common.param.yaml | 7 +++ ...havior_velocity_planner_common.schema.json | 59 +++++++++++++++++++ .../scripts/dilemma_zone_plotter.py | 2 +- 9 files changed, 97 insertions(+), 60 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/config/behavior_velocity_planner_common.param.yaml create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/schema/behavior_velocity_planner_common.schema.json diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index d88601497096d..dad351dec40e8 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -233,6 +233,7 @@ + diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/config/behavior_velocity_planner.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/config/behavior_velocity_planner.param.yaml index b31506918a2db..49749cd1299bd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/config/behavior_velocity_planner.param.yaml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/config/behavior_velocity_planner.param.yaml @@ -4,8 +4,3 @@ backward_path_length: 5.0 behavior_output_path_interval: 1.0 stop_line_extend_length: 5.0 - max_accel: -2.8 - max_jerk: -5.0 - system_delay: 0.5 - delay_response_time: 0.5 - is_publish_debug_path: false # publish all debug path with lane id in each module diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml index 3c4f4c3fdd64c..399762f0b8607 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/launch/behavior_velocity_planner.launch.xml @@ -11,6 +11,7 @@ + @@ -26,7 +27,6 @@ - @@ -53,6 +53,7 @@ + @@ -68,7 +69,5 @@ - - diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/schema/behavior_velocity_planner.schema.json b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/schema/behavior_velocity_planner.schema.json index 67c9c06104b40..80044d5c6af03 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/schema/behavior_velocity_planner.schema.json +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/schema/behavior_velocity_planner.schema.json @@ -21,47 +21,17 @@ "default": "1.0", "description": "the output path will be interpolated by this interval" }, - "max_accel": { - "type": "number", - "default": "-2.8", - "description": "(to be a global parameter) max acceleration of the vehicle" - }, - "system_delay": { - "type": "number", - "default": "0.5", - "description": "(to be a global parameter) delay time until output control command" - }, - "delay_response_time": { - "type": "number", - "default": "0.5", - "description": "(to be a global parameter) delay time of the vehicle's response to control commands" - }, "stop_line_extend_length": { "type": "number", "default": "5.0", "description": "extend length of stop line" - }, - "max_jerk": { - "type": "number", - "default": "-5.0", - "description": "max jerk of the vehicle" - }, - "is_publish_debug_path": { - "type": "boolean", - "default": "false", - "description": "is publish debug path?" } }, "required": [ "forward_path_length", "behavior_output_path_interval", "backward_path_length", - "max_accel", - "system_delay", - "delay_response_time", - "stop_line_extend_length", - "max_jerk", - "is_publish_debug_path" + "stop_line_extend_length" ], "additionalProperties": false } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index cc2f4bf3b96b4..1dfa3163b5b6f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -49,6 +49,8 @@ std::shared_ptr generateNode() const auto autoware_test_utils_dir = ament_index_cpp::get_package_share_directory("autoware_test_utils"); + const auto behavior_velocity_planner_common_dir = + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_planner_common"); const auto behavior_velocity_planner_dir = ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_planner"); const auto velocity_smoother_dir = @@ -82,25 +84,27 @@ std::shared_ptr generateNode() node_options.parameter_overrides(params); autoware::test_utils::updateNodeOptions( - node_options, {autoware_test_utils_dir + "/config/test_common.param.yaml", - autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", - autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", - velocity_smoother_dir + "/config/default_velocity_smoother.param.yaml", - velocity_smoother_dir + "/config/Analytical.param.yaml", - behavior_velocity_planner_dir + "/config/behavior_velocity_planner.param.yaml", - get_behavior_velocity_module_config("blind_spot"), - get_behavior_velocity_module_config("crosswalk"), - get_behavior_velocity_module_config("walkway"), - get_behavior_velocity_module_config("detection_area"), - get_behavior_velocity_module_config("intersection"), - get_behavior_velocity_module_config("no_stopping_area"), - get_behavior_velocity_module_config("occlusion_spot"), - get_behavior_velocity_module_config("run_out"), - get_behavior_velocity_module_config("speed_bump"), - get_behavior_velocity_module_config("stop_line"), - get_behavior_velocity_module_config("traffic_light"), - get_behavior_velocity_module_config("virtual_traffic_light"), - get_behavior_velocity_module_config("no_drivable_lane")}); + node_options, + {autoware_test_utils_dir + "/config/test_common.param.yaml", + autoware_test_utils_dir + "/config/test_nearest_search.param.yaml", + autoware_test_utils_dir + "/config/test_vehicle_info.param.yaml", + velocity_smoother_dir + "/config/default_velocity_smoother.param.yaml", + velocity_smoother_dir + "/config/Analytical.param.yaml", + behavior_velocity_planner_common_dir + "/config/behavior_velocity_planner_common.param.yaml", + behavior_velocity_planner_dir + "/config/behavior_velocity_planner.param.yaml", + get_behavior_velocity_module_config("blind_spot"), + get_behavior_velocity_module_config("crosswalk"), + get_behavior_velocity_module_config("walkway"), + get_behavior_velocity_module_config("detection_area"), + get_behavior_velocity_module_config("intersection"), + get_behavior_velocity_module_config("no_stopping_area"), + get_behavior_velocity_module_config("occlusion_spot"), + get_behavior_velocity_module_config("run_out"), + get_behavior_velocity_module_config("speed_bump"), + get_behavior_velocity_module_config("stop_line"), + get_behavior_velocity_module_config("traffic_light"), + get_behavior_velocity_module_config("virtual_traffic_light"), + get_behavior_velocity_module_config("no_drivable_lane")}); // TODO(Takagi, Isamu): set launch_modules // TODO(Kyoichi Sugahara) set to true launch_virtual_traffic_light diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CMakeLists.txt index 9cb992312f52a..f76fcfa31c240 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CMakeLists.txt @@ -26,4 +26,6 @@ if(BUILD_TESTING) ) endif() -ament_auto_package() +ament_auto_package(INSTALL_TO_SHARE + config +) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/config/behavior_velocity_planner_common.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/config/behavior_velocity_planner_common.param.yaml new file mode 100644 index 0000000000000..aff2aec9cfa29 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/config/behavior_velocity_planner_common.param.yaml @@ -0,0 +1,7 @@ +/**: + ros__parameters: + max_accel: -2.8 + max_jerk: -5.0 + system_delay: 0.5 + delay_response_time: 0.5 + is_publish_debug_path: false # publish all debug path with lane id in each module diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/schema/behavior_velocity_planner_common.schema.json b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/schema/behavior_velocity_planner_common.schema.json new file mode 100644 index 0000000000000..2468b71aa9be1 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/schema/behavior_velocity_planner_common.schema.json @@ -0,0 +1,59 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Behavior Velocity Planner Common", + "type": "object", + "definitions": { + "behavior_velocity_planner_common": { + "type": "object", + "properties": { + "max_accel": { + "type": "number", + "default": "-2.8", + "description": "(to be a global parameter) max acceleration of the vehicle" + }, + "system_delay": { + "type": "number", + "default": "0.5", + "description": "(to be a global parameter) delay time until output control command" + }, + "delay_response_time": { + "type": "number", + "default": "0.5", + "description": "(to be a global parameter) delay time of the vehicle's response to control commands" + }, + "max_jerk": { + "type": "number", + "default": "-5.0", + "description": "max jerk of the vehicle" + }, + "is_publish_debug_path": { + "type": "boolean", + "default": "false", + "description": "is publish debug path?" + } + }, + "required": [ + "max_accel", + "system_delay", + "delay_response_time", + "max_jerk", + "is_publish_debug_path" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/behavior_velocity_planner_common" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py index 55bfbeff893b1..072979a2cef48 100755 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/scripts/dilemma_zone_plotter.py @@ -38,7 +38,7 @@ def get_params_from_yaml(): # get parameters from behavior velocity planner behavior_vel_yaml_file_path = os.path.join( autoware_launch_package_path, - "config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml", + "config/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner_common.param.yaml", ) with open(behavior_vel_yaml_file_path, "r") as yaml_file: params = yaml.safe_load(yaml_file) From 24ef1f93546bc3c3e1ac1b471860fe46b81e3957 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 27 Nov 2024 15:10:17 +0900 Subject: [PATCH 136/273] fix(path_optimizer): solve issue with time keeper (#9483) solve issue with time keeper Signed-off-by: Daniel Sanchez --- planning/autoware_path_optimizer/src/node.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/planning/autoware_path_optimizer/src/node.cpp b/planning/autoware_path_optimizer/src/node.cpp index 62a4882f8a4c1..98bc05d0fe1cf 100644 --- a/planning/autoware_path_optimizer/src/node.cpp +++ b/planning/autoware_path_optimizer/src/node.cpp @@ -222,7 +222,7 @@ void PathOptimizer::resetPreviousData() void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr) { - time_keeper_->start_track(__func__); + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); stop_watch_.tic(); // check if input path is valid @@ -277,8 +277,6 @@ void PathOptimizer::onPath(const Path::ConstSharedPtr path_ptr) autoware::motion_utils::convertToTrajectory(full_traj_points, path_ptr->header); traj_pub_->publish(output_traj_msg); published_time_publisher_->publish_if_subscribed(traj_pub_, output_traj_msg.header.stamp); - - time_keeper_->end_track(__func__); } bool PathOptimizer::checkInputPath(const Path & path, rclcpp::Clock clock) const From bf9b1c21a02b30840fce23c7db5b6f065b45d80c Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 27 Nov 2024 10:20:12 +0100 Subject: [PATCH 137/273] fix: fix missing namespaces in C++ code (#9477) Signed-off-by: Esteve Fernandez --- common/autoware_component_interface_tools/CMakeLists.txt | 2 +- .../src/service_log_checker.cpp | 6 ++++-- .../src/service_log_checker.hpp | 4 +++- .../CMakeLists.txt | 2 +- .../src/traffic_light_recognition_marker_publisher.cpp | 6 +++++- .../src/traffic_light_recognition_marker_publisher.hpp | 3 +++ 6 files changed, 17 insertions(+), 6 deletions(-) diff --git a/common/autoware_component_interface_tools/CMakeLists.txt b/common/autoware_component_interface_tools/CMakeLists.txt index e51db41ca0ea2..ce4af924f4c28 100644 --- a/common/autoware_component_interface_tools/CMakeLists.txt +++ b/common/autoware_component_interface_tools/CMakeLists.txt @@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "ServiceLogChecker" + PLUGIN "autoware::component_interface_tools::ServiceLogChecker" EXECUTABLE service_log_checker_node ) diff --git a/common/autoware_component_interface_tools/src/service_log_checker.cpp b/common/autoware_component_interface_tools/src/service_log_checker.cpp index 18f90af5737d2..ce413da5c1987 100644 --- a/common/autoware_component_interface_tools/src/service_log_checker.cpp +++ b/common/autoware_component_interface_tools/src/service_log_checker.cpp @@ -22,6 +22,8 @@ #define FMT_HEADER_ONLY #include +namespace autoware::component_interface_tools +{ ServiceLogChecker::ServiceLogChecker(const rclcpp::NodeOptions & options) : Node("service_log_checker", options), diagnostics_(this) { @@ -98,6 +100,6 @@ void ServiceLogChecker::update_diagnostics(diagnostic_updater::DiagnosticStatusW stat.summary(DiagnosticStatus::ERROR, "ERROR"); } } - +} // namespace autoware::component_interface_tools #include -RCLCPP_COMPONENTS_REGISTER_NODE(ServiceLogChecker) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::component_interface_tools::ServiceLogChecker) diff --git a/common/autoware_component_interface_tools/src/service_log_checker.hpp b/common/autoware_component_interface_tools/src/service_log_checker.hpp index 9579753dfd900..f6077d238e2e1 100644 --- a/common/autoware_component_interface_tools/src/service_log_checker.hpp +++ b/common/autoware_component_interface_tools/src/service_log_checker.hpp @@ -23,6 +23,8 @@ #include #include +namespace autoware::component_interface_tools +{ class ServiceLogChecker : public rclcpp::Node { public: @@ -38,5 +40,5 @@ class ServiceLogChecker : public rclcpp::Node void update_diagnostics(diagnostic_updater::DiagnosticStatusWrapper & stat); std::unordered_map errors_; }; - +} // namespace autoware::component_interface_tools #endif // SERVICE_LOG_CHECKER_HPP_ diff --git a/common/autoware_traffic_light_recognition_marker_publisher/CMakeLists.txt b/common/autoware_traffic_light_recognition_marker_publisher/CMakeLists.txt index 281a6fc7dc802..1babe2e464fec 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/CMakeLists.txt +++ b/common/autoware_traffic_light_recognition_marker_publisher/CMakeLists.txt @@ -9,7 +9,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "TrafficLightRecognitionMarkerPublisher" + PLUGIN "autoware::traffic_light_recognition_marker_publisher::TrafficLightRecognitionMarkerPublisher" EXECUTABLE ${PROJECT_NAME}_node ) diff --git a/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp b/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp index 5d887a2296137..e9189a6c84c2b 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp +++ b/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp @@ -20,6 +20,8 @@ #include #include +namespace autoware::traffic_light_recognition_marker_publisher +{ TrafficLightRecognitionMarkerPublisher::TrafficLightRecognitionMarkerPublisher( const rclcpp::NodeOptions & options) : Node("traffic_light_recognition_marker_publisher", options) @@ -159,6 +161,8 @@ std_msgs::msg::ColorRGBA TrafficLightRecognitionMarkerPublisher::getTrafficLight return c; // white } +} // namespace autoware::traffic_light_recognition_marker_publisher #include -RCLCPP_COMPONENTS_REGISTER_NODE(TrafficLightRecognitionMarkerPublisher) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::traffic_light_recognition_marker_publisher::TrafficLightRecognitionMarkerPublisher) diff --git a/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp b/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp index 14bb0e39628f9..b4fa388fe0167 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp +++ b/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.hpp @@ -29,6 +29,8 @@ #include #include +namespace autoware::traffic_light_recognition_marker_publisher +{ class TrafficLightRecognitionMarkerPublisher : public rclcpp::Node { public: @@ -58,5 +60,6 @@ class TrafficLightRecognitionMarkerPublisher : public rclcpp::Node bool is_map_ready_ = false; int32_t marker_id = 0; }; +} // namespace autoware::traffic_light_recognition_marker_publisher #endif // TRAFFIC_LIGHT_RECOGNITION_MARKER_PUBLISHER_HPP_ From 85d5bc42166d5e68ab984389115d3a1a68e095e0 Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Wed, 27 Nov 2024 18:58:32 +0900 Subject: [PATCH 138/273] fix(start_planner): use extended current lanes to fix turn signal issue (#9487) fix current lanes issue Signed-off-by: Daniel Sanchez --- .../src/start_planner_module.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 7dd597e27b71f..210afdcd7c1ea 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -1372,7 +1372,7 @@ TurnSignalInfo StartPlannerModule::calcTurnSignalInfo() path.points, status_.pull_out_path.start_pose.position); const auto shift_end_idx = autoware::motion_utils::findNearestIndex(path.points, status_.pull_out_path.end_pose.position); - const lanelet::ConstLanelets current_lanes = utils::getCurrentLanes(planner_data_); + const lanelet::ConstLanelets current_lanes = utils::getExtendedCurrentLanes(planner_data_); const auto is_ignore_signal = [this](const lanelet::Id & id) { if (!ignore_signal_.has_value()) { From a5e9d286220d3985c78ea93fcf188ff3096049c4 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 27 Nov 2024 19:07:31 +0900 Subject: [PATCH 139/273] fix(autoware_image_projection_based_fusion): fix clang-diagnostic-unused-private-field (#9473) * fix: clang-diagnostic-unused-private-field Signed-off-by: kobayu858 * fix: build error Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../autoware_image_projection_based_fusion/CMakeLists.txt | 1 + .../include/autoware/image_projection_based_fusion/debugger.hpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/CMakeLists.txt b/perception/autoware_image_projection_based_fusion/CMakeLists.txt index 73d305d2ab2a8..921a46ccebe3e 100644 --- a/perception/autoware_image_projection_based_fusion/CMakeLists.txt +++ b/perception/autoware_image_projection_based_fusion/CMakeLists.txt @@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 3.14) project(autoware_image_projection_based_fusion) # add_compile_options(-Wno-unknown-pragmas) add_compile_options(-Wno-unknown-pragmas -fopenmp) +add_compile_options(-Wno-error=attributes) find_package(autoware_cmake REQUIRED) find_package(OpenCV REQUIRED) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp index ba7f8b6ca3496..d74347772ef10 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp @@ -56,7 +56,7 @@ class Debugger void imageCallback( const sensor_msgs::msg::Image::ConstSharedPtr input_image_msg, const std::size_t image_id); - rclcpp::Node * node_ptr_; + [[maybe_unused]] rclcpp::Node * node_ptr_; std::shared_ptr image_transport_; std::vector input_camera_topics_; std::vector image_subs_; From 35048a9fd48500d3c554df024475f910a2203633 Mon Sep 17 00:00:00 2001 From: "Kem (TiankuiXian)" <1041084556@qq.com> Date: Wed, 27 Nov 2024 19:32:33 +0900 Subject: [PATCH 140/273] feat(autoware_processing_time_checker): add a trigger to choice whether to output metrics to log folder (#9479) * add output_metrics option. Signed-off-by: xtk8532704 <1041084556@qq.com> * move param set from config to launch file. Signed-off-by: xtk8532704 <1041084556@qq.com> * fix bug. Signed-off-by: xtk8532704 <1041084556@qq.com> --------- Signed-off-by: xtk8532704 <1041084556@qq.com> --- .../README.md | 2 + .../launch/processing_time_checker.launch.xml | 3 + .../package.xml | 2 + .../src/processing_time_checker.cpp | 55 +++++++++++++++++++ .../src/processing_time_checker.hpp | 9 +++ 5 files changed, 71 insertions(+) diff --git a/system/autoware_processing_time_checker/README.md b/system/autoware_processing_time_checker/README.md index 5745ec52086cc..1cb6a289bc54f 100644 --- a/system/autoware_processing_time_checker/README.md +++ b/system/autoware_processing_time_checker/README.md @@ -31,6 +31,8 @@ ros2 launch autoware_processing_time_checker processing_time_checker.launch.xml {{ json_to_markdown("system/autoware_processing_time_checker/schema/processing_time_checker.schema.json") }} +If `output_metrics = true`, the node writes the statics of the processing_time measured during its lifetime to `/autoware_metrics/-.json` when shut down. + ## Assumptions / Known limits TBD. diff --git a/system/autoware_processing_time_checker/launch/processing_time_checker.launch.xml b/system/autoware_processing_time_checker/launch/processing_time_checker.launch.xml index 1e9eb6a3d03e1..9789bd39dca94 100644 --- a/system/autoware_processing_time_checker/launch/processing_time_checker.launch.xml +++ b/system/autoware_processing_time_checker/launch/processing_time_checker.launch.xml @@ -1,7 +1,10 @@ + + + diff --git a/system/autoware_processing_time_checker/package.xml b/system/autoware_processing_time_checker/package.xml index 73a0b43e44c50..16b225f3ef425 100644 --- a/system/autoware_processing_time_checker/package.xml +++ b/system/autoware_processing_time_checker/package.xml @@ -12,6 +12,8 @@ ament_cmake autoware_cmake + autoware_universe_utils + nlohmann-json-dev rclcpp rclcpp_components tier4_debug_msgs diff --git a/system/autoware_processing_time_checker/src/processing_time_checker.cpp b/system/autoware_processing_time_checker/src/processing_time_checker.cpp index 3ab96ab0f9711..262c695d953a6 100644 --- a/system/autoware_processing_time_checker/src/processing_time_checker.cpp +++ b/system/autoware_processing_time_checker/src/processing_time_checker.cpp @@ -14,8 +14,12 @@ #include "processing_time_checker.hpp" +#include #include +#include +#include +#include #include #include @@ -38,6 +42,7 @@ std::string get_last_name(const std::string & str) ProcessingTimeChecker::ProcessingTimeChecker(const rclcpp::NodeOptions & node_options) : Node("processing_time_checker", node_options) { + output_metrics_ = declare_parameter("output_metrics"); const double update_rate = declare_parameter("update_rate"); const auto processing_time_topic_name_list = declare_parameter>("processing_time_topic_name_list"); @@ -64,6 +69,7 @@ ProcessingTimeChecker::ProcessingTimeChecker(const rclcpp::NodeOptions & node_op // register module name if (module_name) { module_name_map_.insert_or_assign(processing_time_topic_name, *module_name); + processing_time_accumulator_map_.insert_or_assign(*module_name, Accumulator()); } else { throw std::invalid_argument("The format of the processing time topic name is not correct."); } @@ -79,6 +85,7 @@ ProcessingTimeChecker::ProcessingTimeChecker(const rclcpp::NodeOptions & node_op processing_time_topic_name, 1, [this, &module_name]([[maybe_unused]] const Float64Stamped & msg) { processing_time_map_.insert_or_assign(module_name, msg.data); + processing_time_accumulator_map_.at(module_name).add(msg.data); })); // clang-format on } @@ -90,6 +97,54 @@ ProcessingTimeChecker::ProcessingTimeChecker(const rclcpp::NodeOptions & node_op this, get_clock(), period_ns, std::bind(&ProcessingTimeChecker::on_timer, this)); } +ProcessingTimeChecker::~ProcessingTimeChecker() +{ + if (!output_metrics_) { + return; + } + + // generate json data + nlohmann::json j; + for (const auto & accumulator_iterator : processing_time_accumulator_map_) { + const auto module_name = accumulator_iterator.first; + const auto processing_time_accumulator = accumulator_iterator.second; + j[module_name + "/min"] = processing_time_accumulator.min(); + j[module_name + "/max"] = processing_time_accumulator.max(); + j[module_name + "/mean"] = processing_time_accumulator.mean(); + j[module_name + "/count"] = processing_time_accumulator.count(); + j[module_name + "/description"] = "processing time of " + module_name + "[ms]"; + } + + // get output folder + const std::string output_folder_str = + rclcpp::get_logging_directory().string() + "/autoware_metrics"; + if (!std::filesystem::exists(output_folder_str)) { + if (!std::filesystem::create_directories(output_folder_str)) { + RCLCPP_ERROR( + this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); + return; + } + } + + // get time stamp + std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::tm * local_time = std::localtime(&now_time_t); + std::ostringstream oss; + oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); + std::string cur_time_str = oss.str(); + + // Write metrics .json to file + const std::string output_file_str = + output_folder_str + "/autoware_processing_time_checker-" + cur_time_str + ".json"; + std::ofstream f(output_file_str); + if (f.is_open()) { + f << j.dump(4); + f.close(); + } else { + RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + } +} + void ProcessingTimeChecker::on_timer() { // create MetricArrayMsg diff --git a/system/autoware_processing_time_checker/src/processing_time_checker.hpp b/system/autoware_processing_time_checker/src/processing_time_checker.hpp index 199410623f8b1..77450923509f2 100644 --- a/system/autoware_processing_time_checker/src/processing_time_checker.hpp +++ b/system/autoware_processing_time_checker/src/processing_time_checker.hpp @@ -15,6 +15,8 @@ #ifndef PROCESSING_TIME_CHECKER_HPP_ #define PROCESSING_TIME_CHECKER_HPP_ +#include "autoware/universe_utils/math/accumulator.hpp" + #include #include @@ -27,6 +29,7 @@ namespace autoware::processing_time_checker { +using autoware::universe_utils::Accumulator; using MetricMsg = tier4_metric_msgs::msg::Metric; using MetricArrayMsg = tier4_metric_msgs::msg::MetricArray; using tier4_debug_msgs::msg::Float64Stamped; @@ -35,6 +38,7 @@ class ProcessingTimeChecker : public rclcpp::Node { public: explicit ProcessingTimeChecker(const rclcpp::NodeOptions & node_options); + ~ProcessingTimeChecker() override; private: void on_timer(); @@ -44,10 +48,15 @@ class ProcessingTimeChecker : public rclcpp::Node rclcpp::Publisher::SharedPtr metrics_pub_; std::vector::SharedPtr> processing_time_subscribers_; + // parameters + bool output_metrics_; + // topic name - module name std::unordered_map module_name_map_{}; // module name - processing time std::unordered_map processing_time_map_{}; + // module name - accumulator + std::unordered_map> processing_time_accumulator_map_{}; }; } // namespace autoware::processing_time_checker From 9c7f45f7c707209c24a6f82876ae56a5378ebab3 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 27 Nov 2024 20:17:02 +0900 Subject: [PATCH 141/273] fix(bag_time_manager_rviz_plugin): fix clang-diagnostic-unused-lambda-capture (#9444) Signed-off-by: veqcc --- .../src/bag_time_manager_panel.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp b/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp index 79da89bd9e981..ef52977cb7e73 100644 --- a/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp +++ b/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp @@ -82,7 +82,7 @@ void BagTimeManagerPanel::onPauseClicked() pause_button_->setStyleSheet("background-color: #00FF00;"); auto req = std::make_shared(); client_resume_->async_send_request( - req, [this]([[maybe_unused]] rclcpp::Client::SharedFuture result) {}); + req, []([[maybe_unused]] rclcpp::Client::SharedFuture result) {}); } else { // do pause current_state_ = STATE::PAUSE; @@ -91,7 +91,7 @@ void BagTimeManagerPanel::onPauseClicked() pause_button_->setStyleSheet("background-color: #FF0000;"); auto req = std::make_shared(); client_pause_->async_send_request( - req, [this]([[maybe_unused]] rclcpp::Client::SharedFuture result) {}); + req, []([[maybe_unused]] rclcpp::Client::SharedFuture result) {}); } } From 4fc74ae7386cbc04e836de4d46221474581a5d27 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 27 Nov 2024 20:39:58 +0900 Subject: [PATCH 142/273] fix(goal_planner): fix multiple lane ids of shift pull over (#9360) Signed-off-by: kosuke55 fix vel --- .../src/pull_over_planner/shift_pull_over.cpp | 36 +++++++++---------- 1 file changed, 17 insertions(+), 19 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index da99c830c68bb..4bdec4a285d75 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -218,14 +218,23 @@ std::optional ShiftPullOver::generatePullOverPath( shifted_path.path.points.push_back(p); } + // combine road lanes and shoulder lanes to find closest lanelet id + const auto lanes = std::invoke([&]() -> lanelet::ConstLanelets { + auto lanes = road_lanes; + lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end()); + return lanes; // not copy the value (Return Value Optimization) + }); + // set goal pose with velocity 0 { PathPointWithLaneId p{}; p.point.longitudinal_velocity_mps = 0.0; p.point.pose = goal_pose; - p.lane_ids = shifted_path.path.points.back().lane_ids; - for (const auto & lane : pull_over_lanes) { - p.lane_ids.push_back(lane.id()); + lanelet::Lanelet goal_lanelet{}; + if (lanelet::utils::query::getClosestLanelet(lanes, goal_pose, &goal_lanelet)) { + p.lane_ids = {goal_lanelet.id()}; + } else { + p.lane_ids = shifted_path.path.points.back().lane_ids; } shifted_path.path.points.push_back(p); } @@ -234,24 +243,13 @@ std::optional ShiftPullOver::generatePullOverPath( for (size_t i = path_shifter.getShiftLines().front().start_idx; i < shifted_path.path.points.size() - 1; ++i) { auto & point = shifted_path.path.points.at(i); - // set velocity point.point.longitudinal_velocity_mps = std::min(point.point.longitudinal_velocity_mps, static_cast(pull_over_velocity)); - - // add target lanes to points after shift start - // add road lane_ids if not found - for (const auto id : shifted_path.path.points.back().lane_ids) { - if (std::find(point.lane_ids.begin(), point.lane_ids.end(), id) == point.lane_ids.end()) { - point.lane_ids.push_back(id); - } - } - // add shoulder lane_id if not found - for (const auto & lane : pull_over_lanes) { - if ( - std::find(point.lane_ids.begin(), point.lane_ids.end(), lane.id()) == - point.lane_ids.end()) { - point.lane_ids.push_back(lane.id()); - } + lanelet::Lanelet lanelet{}; + if (lanelet::utils::query::getClosestLanelet(lanes, point.point.pose, &lanelet)) { + point.lane_ids = {lanelet.id()}; // overwrite lane_ids + } else { + point.lane_ids = shifted_path.path.points.at(i - 1).lane_ids; } } From c3df6b1b509425935ac0afc47eefadd390b5e237 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 27 Nov 2024 13:14:34 +0100 Subject: [PATCH 143/273] chore(autoware_pyplot): move to visualization folder (#9489) Signed-off-by: Esteve Fernandez --- {common => visualization}/autoware_pyplot/CMakeLists.txt | 0 .../autoware_pyplot/include/autoware/pyplot/axes.hpp | 0 .../autoware_pyplot/include/autoware/pyplot/common.hpp | 0 .../autoware_pyplot/include/autoware/pyplot/figure.hpp | 0 .../autoware_pyplot/include/autoware/pyplot/legend.hpp | 0 .../autoware_pyplot/include/autoware/pyplot/loader.hpp | 0 .../autoware_pyplot/include/autoware/pyplot/patches.hpp | 0 .../autoware_pyplot/include/autoware/pyplot/pyplot.hpp | 0 .../autoware_pyplot/include/autoware/pyplot/quiver.hpp | 0 .../autoware_pyplot/include/autoware/pyplot/text.hpp | 0 {common => visualization}/autoware_pyplot/package.xml | 0 {common => visualization}/autoware_pyplot/src/axes.cpp | 0 {common => visualization}/autoware_pyplot/src/common.cpp | 0 {common => visualization}/autoware_pyplot/src/figure.cpp | 0 {common => visualization}/autoware_pyplot/src/legend.cpp | 0 {common => visualization}/autoware_pyplot/src/patches.cpp | 0 {common => visualization}/autoware_pyplot/src/pyplot.cpp | 0 {common => visualization}/autoware_pyplot/src/quiver.cpp | 0 {common => visualization}/autoware_pyplot/src/text.cpp | 0 {common => visualization}/autoware_pyplot/test/test_pyplot.cpp | 0 20 files changed, 0 insertions(+), 0 deletions(-) rename {common => visualization}/autoware_pyplot/CMakeLists.txt (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/axes.hpp (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/common.hpp (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/figure.hpp (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/legend.hpp (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/loader.hpp (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/patches.hpp (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/pyplot.hpp (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/quiver.hpp (100%) rename {common => visualization}/autoware_pyplot/include/autoware/pyplot/text.hpp (100%) rename {common => visualization}/autoware_pyplot/package.xml (100%) rename {common => visualization}/autoware_pyplot/src/axes.cpp (100%) rename {common => visualization}/autoware_pyplot/src/common.cpp (100%) rename {common => visualization}/autoware_pyplot/src/figure.cpp (100%) rename {common => visualization}/autoware_pyplot/src/legend.cpp (100%) rename {common => visualization}/autoware_pyplot/src/patches.cpp (100%) rename {common => visualization}/autoware_pyplot/src/pyplot.cpp (100%) rename {common => visualization}/autoware_pyplot/src/quiver.cpp (100%) rename {common => visualization}/autoware_pyplot/src/text.cpp (100%) rename {common => visualization}/autoware_pyplot/test/test_pyplot.cpp (100%) diff --git a/common/autoware_pyplot/CMakeLists.txt b/visualization/autoware_pyplot/CMakeLists.txt similarity index 100% rename from common/autoware_pyplot/CMakeLists.txt rename to visualization/autoware_pyplot/CMakeLists.txt diff --git a/common/autoware_pyplot/include/autoware/pyplot/axes.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/axes.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/axes.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/axes.hpp diff --git a/common/autoware_pyplot/include/autoware/pyplot/common.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/common.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/common.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/common.hpp diff --git a/common/autoware_pyplot/include/autoware/pyplot/figure.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/figure.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/figure.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/figure.hpp diff --git a/common/autoware_pyplot/include/autoware/pyplot/legend.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/legend.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/legend.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/legend.hpp diff --git a/common/autoware_pyplot/include/autoware/pyplot/loader.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/loader.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/loader.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/loader.hpp diff --git a/common/autoware_pyplot/include/autoware/pyplot/patches.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/patches.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/patches.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/patches.hpp diff --git a/common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/pyplot.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/pyplot.hpp diff --git a/common/autoware_pyplot/include/autoware/pyplot/quiver.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/quiver.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/quiver.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/quiver.hpp diff --git a/common/autoware_pyplot/include/autoware/pyplot/text.hpp b/visualization/autoware_pyplot/include/autoware/pyplot/text.hpp similarity index 100% rename from common/autoware_pyplot/include/autoware/pyplot/text.hpp rename to visualization/autoware_pyplot/include/autoware/pyplot/text.hpp diff --git a/common/autoware_pyplot/package.xml b/visualization/autoware_pyplot/package.xml similarity index 100% rename from common/autoware_pyplot/package.xml rename to visualization/autoware_pyplot/package.xml diff --git a/common/autoware_pyplot/src/axes.cpp b/visualization/autoware_pyplot/src/axes.cpp similarity index 100% rename from common/autoware_pyplot/src/axes.cpp rename to visualization/autoware_pyplot/src/axes.cpp diff --git a/common/autoware_pyplot/src/common.cpp b/visualization/autoware_pyplot/src/common.cpp similarity index 100% rename from common/autoware_pyplot/src/common.cpp rename to visualization/autoware_pyplot/src/common.cpp diff --git a/common/autoware_pyplot/src/figure.cpp b/visualization/autoware_pyplot/src/figure.cpp similarity index 100% rename from common/autoware_pyplot/src/figure.cpp rename to visualization/autoware_pyplot/src/figure.cpp diff --git a/common/autoware_pyplot/src/legend.cpp b/visualization/autoware_pyplot/src/legend.cpp similarity index 100% rename from common/autoware_pyplot/src/legend.cpp rename to visualization/autoware_pyplot/src/legend.cpp diff --git a/common/autoware_pyplot/src/patches.cpp b/visualization/autoware_pyplot/src/patches.cpp similarity index 100% rename from common/autoware_pyplot/src/patches.cpp rename to visualization/autoware_pyplot/src/patches.cpp diff --git a/common/autoware_pyplot/src/pyplot.cpp b/visualization/autoware_pyplot/src/pyplot.cpp similarity index 100% rename from common/autoware_pyplot/src/pyplot.cpp rename to visualization/autoware_pyplot/src/pyplot.cpp diff --git a/common/autoware_pyplot/src/quiver.cpp b/visualization/autoware_pyplot/src/quiver.cpp similarity index 100% rename from common/autoware_pyplot/src/quiver.cpp rename to visualization/autoware_pyplot/src/quiver.cpp diff --git a/common/autoware_pyplot/src/text.cpp b/visualization/autoware_pyplot/src/text.cpp similarity index 100% rename from common/autoware_pyplot/src/text.cpp rename to visualization/autoware_pyplot/src/text.cpp diff --git a/common/autoware_pyplot/test/test_pyplot.cpp b/visualization/autoware_pyplot/test/test_pyplot.cpp similarity index 100% rename from common/autoware_pyplot/test/test_pyplot.cpp rename to visualization/autoware_pyplot/test/test_pyplot.cpp From e6d90b700285b3b58ce38b36782dae4a9f40798a Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 27 Nov 2024 21:53:14 +0900 Subject: [PATCH 144/273] fix(autoware_lidar_transfusion): fix clang-diagnostic-unused-private-field (#9499) Signed-off-by: kobayu858 --- .../autoware/lidar_transfusion/lidar_transfusion_node.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/lidar_transfusion_node.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/lidar_transfusion_node.hpp index e19d2d49af998..466c2202de3e3 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/lidar_transfusion_node.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/lidar_transfusion_node.hpp @@ -55,7 +55,6 @@ class LIDAR_TRANSFUSION_PUBLIC LidarTransfusionNode : public rclcpp::Node tf2_ros::TransformListener tf_listener_{tf_buffer_}; DetectionClassRemapper detection_class_remapper_; - float score_threshold_{0.0}; std::vector class_names_; NonMaximumSuppression iou_bev_nms_; From cc8abac719521669795a006b7a21e46aabaeb7d2 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 27 Nov 2024 22:57:36 +0900 Subject: [PATCH 145/273] fix(autoware_raindrop_cluster_filter): fix clang-diagnostic-unused-private-field (#9496) Signed-off-by: kobayu858 --- .../src/low_intensity_cluster_filter_node.hpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.hpp b/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.hpp index 61e23860cd195..5f2dc05ba7eff 100644 --- a/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.hpp +++ b/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.hpp @@ -56,13 +56,8 @@ class LowIntensityClusterFilter : public rclcpp::Node double max_y_; double min_y_; - double max_x_transformed_; - double min_x_transformed_; - double max_y_transformed_; - double min_y_transformed_; // Eigen::Vector4f min_boundary_transformed_; // Eigen::Vector4f max_boundary_transformed_; - bool is_validation_range_transformed_ = false; const std::string base_link_frame_id_ = "base_link"; autoware::detected_object_validation::utils::FilterTargetLabel filter_target_; From 2fbacc7b559be1782884ececf3ab791effd59453 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 09:12:32 +0900 Subject: [PATCH 146/273] fix(autoware_tracking_object_merger): fix clang-diagnostic-sign-conversion (#9494) Signed-off-by: kobayu858 --- .../src/association/data_association.cpp | 20 +++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/perception/autoware_tracking_object_merger/src/association/data_association.cpp b/perception/autoware_tracking_object_merger/src/association/data_association.cpp index 771fcb5f1a484..461dfb8ef14ce 100644 --- a/perception/autoware_tracking_object_merger/src/association/data_association.cpp +++ b/perception/autoware_tracking_object_merger/src/association/data_association.cpp @@ -94,11 +94,11 @@ void DataAssociation::assign( const Eigen::MatrixXd & src, std::unordered_map & direct_assignment, std::unordered_map & reverse_assignment) { - std::vector> score(src.rows()); + std::vector> score(static_cast(src.rows())); for (int row = 0; row < src.rows(); ++row) { - score.at(row).resize(src.cols()); + score.at(static_cast(row)).resize(static_cast(src.cols())); for (int col = 0; col < src.cols(); ++col) { - score.at(row).at(col) = src(row, col); + score.at(static_cast(row)).at(static_cast(col)) = src(row, col); } } // Solve @@ -134,15 +134,17 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( const autoware_perception_msgs::msg::TrackedObjects & objects0, const autoware_perception_msgs::msg::TrackedObjects & objects1) { - Eigen::MatrixXd score_matrix = - Eigen::MatrixXd::Zero(objects1.objects.size(), objects0.objects.size()); + Eigen::MatrixXd score_matrix = Eigen::MatrixXd::Zero( + static_cast(objects1.objects.size()), + static_cast(objects0.objects.size())); for (size_t objects1_idx = 0; objects1_idx < objects1.objects.size(); ++objects1_idx) { const auto & object1 = objects1.objects.at(objects1_idx); for (size_t objects0_idx = 0; objects0_idx < objects0.objects.size(); ++objects0_idx) { const auto & object0 = objects0.objects.at(objects0_idx); const double score = calcScoreBetweenObjects(object0, object1); - score_matrix(objects1_idx, objects0_idx) = score; + score_matrix( + static_cast(objects1_idx), static_cast(objects0_idx)) = score; } } return score_matrix; @@ -159,7 +161,8 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( const autoware_perception_msgs::msg::TrackedObjects & objects0, const std::vector & trackers) { - Eigen::MatrixXd score_matrix = Eigen::MatrixXd::Zero(trackers.size(), objects0.objects.size()); + Eigen::MatrixXd score_matrix = Eigen::MatrixXd::Zero( + static_cast(trackers.size()), static_cast(objects0.objects.size())); for (size_t trackers_idx = 0; trackers_idx < trackers.size(); ++trackers_idx) { const auto & object1 = trackers.at(trackers_idx).getObject(); @@ -167,7 +170,8 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix( const auto & object0 = objects0.objects.at(objects0_idx); const double score = calcScoreBetweenObjects(object0, object1); - score_matrix(trackers_idx, objects0_idx) = score; + score_matrix( + static_cast(trackers_idx), static_cast(objects0_idx)) = score; } } return score_matrix; From 4e939603779a70eae27d7e98819c7edabc443cd9 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 09:12:55 +0900 Subject: [PATCH 147/273] fix(autoware_multi_object_tracker): fix clang-diagnostic-unused-private-field (#9491) Signed-off-by: kobayu858 --- .../src/debugger/debug_object.hpp | 1 - .../src/processor/input_manager.hpp | 3 --- 2 files changed, 4 deletions(-) diff --git a/perception/autoware_multi_object_tracker/src/debugger/debug_object.hpp b/perception/autoware_multi_object_tracker/src/debugger/debug_object.hpp index c77b465fb2bc9..e564afc9fd9d0 100644 --- a/perception/autoware_multi_object_tracker/src/debugger/debug_object.hpp +++ b/perception/autoware_multi_object_tracker/src/debugger/debug_object.hpp @@ -77,7 +77,6 @@ class TrackerObjectDebugger std::vector object_data_list_; std::list unused_marker_ids_; - int32_t marker_id_ = 0; std::vector> object_data_groups_; std::vector channel_names_; 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 f8b221f733faa..25ee6b5eb0d5a 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp @@ -88,7 +88,6 @@ class InputStream // bool is_time_initialized_{false}; int initial_count_{0}; - double expected_interval_{}; double latency_mean_{}; double latency_var_{}; double interval_mean_{}; @@ -130,8 +129,6 @@ class InputManager double target_stream_latency_std_{0.04}; // [s] double target_stream_interval_{0.1}; // [s] double target_stream_interval_std_{0.02}; // [s] - double target_latency_{0.2}; // [s] - double target_latency_band_{1.0}; // [s] private: void getObjectTimeInterval( From 08621e6e8c90627ded0356e0906abd9797f531fa Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Thu, 28 Nov 2024 11:00:37 +0900 Subject: [PATCH 148/273] fix(autoware_processing_time_checker): fix typo (#9504) Signed-off-by: veqcc --- .../src/processing_time_checker.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/system/autoware_processing_time_checker/src/processing_time_checker.cpp b/system/autoware_processing_time_checker/src/processing_time_checker.cpp index 262c695d953a6..1e3f04af8fa89 100644 --- a/system/autoware_processing_time_checker/src/processing_time_checker.cpp +++ b/system/autoware_processing_time_checker/src/processing_time_checker.cpp @@ -52,7 +52,7 @@ ProcessingTimeChecker::ProcessingTimeChecker(const rclcpp::NodeOptions & node_op // extract module name from topic name auto tmp_topic_name = processing_time_topic_name; - for (size_t i = 0; i < 4; ++i) { // 4 is enouh for the search depth + for (size_t i = 0; i < 4; ++i) { // 4 is enough for the search depth tmp_topic_name = remove_last_name(tmp_topic_name); const auto module_name_candidate = get_last_name(tmp_topic_name); // clang-format off From c4608ad6c3ad189e28a16cea4dde9bb58f85ebd0 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 28 Nov 2024 11:29:59 +0900 Subject: [PATCH 149/273] feat(lane_change): improve delay lane change logic (#9480) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * implement function to check if lane change delay is required Signed-off-by: mohammad alqudah * refactor function isParkedObject Signed-off-by: mohammad alqudah * refactor delay lane change parameters Signed-off-by: mohammad alqudah * update lc param yaml Signed-off-by: mohammad alqudah * separate target lane leading objects based on behavior (RT1-8532) Signed-off-by: Zulfaqar Azmi * fixed overlapped filtering and lanes debug marker Signed-off-by: Zulfaqar Azmi * combine filteredObjects function Signed-off-by: Zulfaqar Azmi * renaming functions and type Signed-off-by: Zulfaqar Azmi * update some logic to check is stopped Signed-off-by: Zulfaqar Azmi * rename expanded to stopped_outside_boundary Signed-off-by: Zulfaqar Azmi * Include docstring Signed-off-by: Zulfaqar Azmi * rename stopped_outside_boundary → stopped_at_bound Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> Signed-off-by: Zulfaqar Azmi * spell-check Signed-off-by: Zulfaqar Azmi * add docstring for function is_delay_lane_change Signed-off-by: mohammad alqudah * remove unused functions Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * add delay parameters to README Signed-off-by: mohammad alqudah * add documentation for delay lane change behavior Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * run pre-commit checks Signed-off-by: mohammad alqudah * only check for delay lc if feature is enabled Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah Signed-off-by: Zulfaqar Azmi Co-authored-by: Zulfaqar Azmi Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> --- .../README.md | 76 +- .../config/lane_change.param.yaml | 11 +- .../images/delay_lane_change_1.drawio.svg | 657 +++++++++++++++++ .../images/delay_lane_change_2.drawio.svg | 625 ++++++++++++++++ .../images/delay_lane_change_3.drawio.svg | 683 ++++++++++++++++++ .../images/delay_lane_change_4.drawio.svg | 683 ++++++++++++++++++ .../images/delay_lane_change_5.drawio.svg | 677 +++++++++++++++++ .../utils/parameters.hpp | 9 + .../utils/utils.hpp | 29 +- .../src/manager.cpp | 15 +- .../src/scene.cpp | 8 +- .../src/utils/utils.cpp | 198 ++--- 12 files changed, 3495 insertions(+), 176 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_1.drawio.svg create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_2.drawio.svg create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_3.drawio.svg create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_4.drawio.svg create mode 100644 planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_5.drawio.svg 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 6ebe79c180e95..d24a89bf03000 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 @@ -351,6 +351,71 @@ stop @enduml ``` +#### Delay Lane Change Check + +In certain situations, when there are stopped vehicles along the target lane ahead of Ego vehicle, to avoid getting stuck, it is desired to perform the lane change maneuver after the stopped vehicle. +To do so, all static objects ahead of ego along the target lane are checked in order from closest to furthest, if any object satisfies the following conditions, lane change will be delayed and candidate path will be rejected. + +1. The distance from object to terminal end is sufficient to perform lane change +2. The distance to object is less than the lane changing length +3. The distance from object to next object is sufficient to perform lane change + +If the parameter `check_only_parked_vehicle` is set to `true`, the check will only consider objects which are determined as parked. + +The following flow chart illustrates the delay lane change check. + +```plantuml +@startuml +skinparam defaultTextAlignment center +skinparam backgroundColor #White + +start +if (Is target objects, candidate path, OR current lane path empty?) then (yes) + #LightPink:Return false; + stop +else (no) +endif + +:Start checking objects from closest to furthest; +repeat + if (Is distance from object to terminal sufficient) then (yes) + else (no) + #LightPink:Return false; + stop + endif + + if (Is distance to object less than lane changing length) then (yes) + else (no) + if (Is only check parked vehicles and vehicle is not parked) then (yes) + else (no) + if(Is last object OR distance to next object is sufficient) then (yes) + #LightGreen: Return true; + stop + else (no) + endif + endif + endif + repeat while (Is finished checking all objects) is (FALSE) + +#LightPink: Return false; +stop + +@enduml +``` + +The following figures demonstrate different situations under which will or will not be triggered: + +1. Delay lane change will be triggered as there is sufficient distance ahead. + ![delay lane change 1](./images/delay_lane_change_1.drawio.svg) +2. Delay lane change will NOT be triggered as there is no sufficient distance ahead + ![delay lane change 2](./images/delay_lane_change_2.drawio.svg) +3. Delay lane change will be triggered by fist NPC as there is sufficient distance ahead. + ![delay lane change 3](./images/delay_lane_change_3.drawio.svg) +4. Delay lane change will be triggered by second NPC as there is sufficient distance ahead + ![delay lane change 4](./images/delay_lane_change_4.drawio.svg) +5. Delay lane change will NOT be triggered as there is no sufficient distance ahead. + ![delay lane change 5](./images/delay_lane_change_5.drawio.svg) + #### Candidate Path's Safety check See [safety check utils explanation](../autoware_behavior_path_planner_common/docs/behavior_path_planner_safety_check.md) @@ -828,8 +893,6 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | `trajectory.lat_acc_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | | `trajectory.max_longitudinal_acc` | [m/s2] | double | maximum longitudinal acceleration for lane change | 1.0 | | `trajectory.min_longitudinal_acc` | [m/s2] | double | maximum longitudinal deceleration for lane change | -1.0 | -| `object_check_min_road_shoulder_width` | [m] | double | Width considered as a road shoulder if the lane does not have a road shoulder | 0.5 | -| `object_shiftable_ratio_threshold` | [-] | double | Vehicles around the center line within this distance ratio will be excluded from parking objects | 0.6 | | `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | | `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | | `lateral_acceleration.min_values` | [m/s2] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] | @@ -860,6 +923,15 @@ The following parameters are used to judge lane change completion. | `stuck_detection.velocity` | [m/s] | double | Velocity threshold for ego vehicle stuck detection | 0.1 | | `stuck_detection.stop_time` | [s] | double | Stop time threshold for ego vehicle stuck detection | 3.0 | +### Delay Lane Change + +| Name | Unit | Type | Description | Default value | +| :------------------------------------------------ | ---- | ------ | ----------------------------------------------------------------------------------------------------- | ------------- | +| `delay_lane_change.enable` | [-] | bool | Flag to enable/disable lane change delay feature | true | +| `delay_lane_change.check_only_parked_vehicle` | [-] | bool | Flag to limit delay feature for only parked vehicles | false | +| `delay_lane_change.min_road_shoulder_width` | [m] | double | Width considered as road shoulder if lane doesn't have road shoulder when checking for parked vehicle | 0.5 | +| `delay_lane_change.th_parked_vehicle_shift_ratio` | [-] | double | Stopped vehicles beyond this distance ratio from center line will be considered as parked | 0.6 | + ### Collision checks #### Target Objects 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 6ac4544f2b342..6baf05edad484 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,10 +6,6 @@ backward_length_buffer_for_blocking_object: 3.0 # [m] backward_length_from_intersection: 5.0 # [m] - # side walk parked vehicle - object_check_min_road_shoulder_width: 0.5 # [m] - object_shiftable_ratio_threshold: 0.6 - # turn signal min_length_for_turn_signal_activation: 10.0 # [m] @@ -25,6 +21,13 @@ lon_acc_sampling_num: 5 lat_acc_sampling_num: 3 + # delay lane change + delay_lane_change: + enable: true + check_only_parked_vehicle: false + min_road_shoulder_width: 0.5 # [m] + th_parked_vehicle_shift_ratio: 0.6 + # safety check safety_check: allow_loose_check_for_cancel: true diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_1.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_1.drawio.svg new file mode 100644 index 0000000000000..f5f3e4e88559b --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_1.drawio.svg @@ -0,0 +1,657 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_2.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_2.drawio.svg new file mode 100644 index 0000000000000..8237ac312aadb --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_2.drawio.svg @@ -0,0 +1,625 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_3.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_3.drawio.svg new file mode 100644 index 0000000000000..2bcbfb5cdb93d --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_3.drawio.svg @@ -0,0 +1,683 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_4.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_4.drawio.svg new file mode 100644 index 0000000000000..b38092183db14 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_4.drawio.svg @@ -0,0 +1,683 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_5.drawio.svg b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_5.drawio.svg new file mode 100644 index 0000000000000..d4abb53a84999 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/images/delay_lane_change_5.drawio.svg @@ -0,0 +1,677 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp index d688782ed8d8d..7f97eb872f795 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp @@ -127,11 +127,20 @@ struct TrajectoryParameters LateralAccelerationMap lat_acc_map{}; }; +struct DelayParameters +{ + bool enable{true}; + bool check_only_parked_vehicle{false}; + double min_road_shoulder_width{0.5}; + double th_parked_vehicle_shift_ratio{0.6}; +}; + struct Parameters { TrajectoryParameters trajectory{}; SafetyParameters safety{}; CancelParameters cancel{}; + DelayParameters delay{}; // lane change parameters double backward_lane_length{200.0}; 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 a02a61d5e72b6..2ec9d4cdf4e4e 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 @@ -132,14 +132,29 @@ bool isParkedObject( const ExtendedPredictedObject & object, const double buffer_to_bound, const double ratio_threshold); -bool passed_parked_objects( +/** + * @brief Checks if delaying of lane change maneuver is necessary + * + * @details Scans through the provided target objects (assumed to be ordered from closest to + * furthest), and returns true if any of the objects satisfy the following conditions: + * - Not near the end of current lanes + * - There is sufficient distance from object to next one to do lane change + * If the parameter delay_lc_param.check_only_parked_vehicle is set to True, only objects + * which pass isParkedObject() check will be considered. + * + * @param common_data_ptr Shared pointer to CommonData that holds necessary lanes info, parameters, + * and transient data. + * @param lane_change_path Candidate lane change path to apply checks on. + * @param target_objects Relevant objects to consider for delay LC checks (assumed to only include + * target lane leading static objects). + * @param object_debug Collision check debug struct to be updated if any of the target objects + * satisfy the conditions. + * @return bool True if conditions to delay lane change are met + */ +bool is_delay_lane_change( const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, - const std::vector & objects, CollisionCheckDebugMap & object_debug); - -std::optional getLeadingStaticObjectIdx( - const RouteHandler & route_handler, const LaneChangePath & lane_change_path, - const std::vector & objects, - const double object_check_min_road_shoulder_width, const double object_shiftable_ratio_threshold); + const std::vector & target_objects, + CollisionCheckDebugMap & object_debug); lanelet::BasicPolygon2d create_polygon( const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist); 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 2624d0f1a87c6..fc419f149e2b9 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 @@ -99,12 +99,6 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s } } - // parked vehicle detection - p.object_check_min_road_shoulder_width = - getOrDeclareParameter(*node, parameter("object_check_min_road_shoulder_width")); - p.th_object_shiftable_ratio = - getOrDeclareParameter(*node, parameter("object_shiftable_ratio_threshold")); - // turn signal p.min_length_for_turn_signal_activation = getOrDeclareParameter(*node, parameter("min_length_for_turn_signal_activation")); @@ -203,6 +197,15 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s "Lane change buffer must be more than 1 meter. Modifying the buffer."); } + // lane change delay + p.delay.enable = getOrDeclareParameter(*node, parameter("delay_lane_change.enable")); + p.delay.check_only_parked_vehicle = + getOrDeclareParameter(*node, parameter("delay_lane_change.check_only_parked_vehicle")); + p.delay.min_road_shoulder_width = + getOrDeclareParameter(*node, parameter("delay_lane_change.min_road_shoulder_width")); + p.delay.th_parked_vehicle_shift_ratio = getOrDeclareParameter( + *node, parameter("delay_lane_change.th_parked_vehicle_shift_ratio")); + // lane change cancel p.cancel.enable_on_prepare_phase = getOrDeclareParameter(*node, parameter("cancel.enable_on_prepare_phase")); 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 2e9b9e337e51c..c6d8248be134c 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 @@ -1341,7 +1341,7 @@ bool NormalLaneChange::check_candidate_path_safety( } if ( - !is_stuck && !utils::lane_change::passed_parked_objects( + !is_stuck && utils::lane_change::is_delay_lane_change( common_data_ptr_, candidate_path, filtered_objects_.target_lane_leading.stopped, lane_change_debug_.collision_check_objects)) { throw std::logic_error( @@ -1522,10 +1522,8 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const return {false, true}; } - const auto has_passed_parked_objects = utils::lane_change::passed_parked_objects( - common_data_ptr_, path, filtered_objects_.target_lane_leading.stopped, debug_data); - - if (!has_passed_parked_objects) { + if (utils::lane_change::is_delay_lane_change( + common_data_ptr_, path, filtered_objects_.target_lane_leading.stopped, debug_data)) { RCLCPP_DEBUG(logger_, "Lane change has been delayed."); return {false, false}; } 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 ff8bb971405ad..db0c1cb37abbb 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 @@ -668,9 +668,6 @@ bool isParkedObject( // +: object position // o: nearest point on centerline - using lanelet::geometry::distance2d; - using lanelet::geometry::toArcCoordinates; - const double object_vel_norm = std::hypot(object.initial_twist.linear.x, object.initial_twist.linear.y); if (object_vel_norm > static_object_velocity_threshold) { @@ -689,49 +686,15 @@ bool isParkedObject( const double lat_dist = autoware::motion_utils::calcLateralOffset(path.points, object_pose.position); - lanelet::BasicLineString2d bound; - double center_to_bound_buffer = 0.0; - if (lat_dist > 0.0) { - // left side vehicle - const auto most_left_road_lanelet = route_handler.getMostLeftLanelet(closest_lanelet); - const auto most_left_lanelet_candidates = - route_handler.getLaneletMapPtr()->laneletLayer.findUsages(most_left_road_lanelet.leftBound()); - lanelet::ConstLanelet most_left_lanelet = most_left_road_lanelet; - const lanelet::Attribute most_left_sub_type = - most_left_lanelet.attribute(lanelet::AttributeName::Subtype); - - for (const auto & ll : most_left_lanelet_candidates) { - const auto & sub_type = ll.attribute(lanelet::AttributeName::Subtype); - if (sub_type.value() == "road_shoulder") { - most_left_lanelet = ll; - } - } - bound = most_left_lanelet.leftBound2d().basicLineString(); - if (most_left_sub_type.value() != "road_shoulder") { - center_to_bound_buffer = object_check_min_road_shoulder_width; - } - } else { - // right side vehicle - const auto most_right_road_lanelet = route_handler.getMostRightLanelet(closest_lanelet); - const auto most_right_lanelet_candidates = - route_handler.getLaneletMapPtr()->laneletLayer.findUsages( - most_right_road_lanelet.rightBound()); - - lanelet::ConstLanelet most_right_lanelet = most_right_road_lanelet; - const lanelet::Attribute most_right_sub_type = - most_right_lanelet.attribute(lanelet::AttributeName::Subtype); - - for (const auto & ll : most_right_lanelet_candidates) { - const auto & sub_type = ll.attribute(lanelet::AttributeName::Subtype); - if (sub_type.value() == "road_shoulder") { - most_right_lanelet = ll; - } - } - bound = most_right_lanelet.rightBound2d().basicLineString(); - if (most_right_sub_type.value() != "road_shoulder") { - center_to_bound_buffer = object_check_min_road_shoulder_width; - } - } + const auto most_side_lanelet = + lat_dist > 0.0 ? route_handler.getMostLeftLanelet(closest_lanelet, false, true) + : route_handler.getMostRightLanelet(closest_lanelet, false, true); + const auto bound = lat_dist > 0.0 ? most_side_lanelet.leftBound2d().basicLineString() + : most_side_lanelet.rightBound2d().basicLineString(); + const lanelet::Attribute lanelet_sub_type = + most_side_lanelet.attribute(lanelet::AttributeName::Subtype); + const auto center_to_bound_buffer = + lanelet_sub_type.value() == "road_shoulder" ? 0.0 : object_check_min_road_shoulder_width; return isParkedObject( closest_lanelet, bound, object, center_to_bound_buffer, object_shiftable_ratio_threshold); @@ -776,129 +739,60 @@ bool isParkedObject( return clamped_ratio > ratio_threshold; } -bool passed_parked_objects( +bool is_delay_lane_change( const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, - const std::vector & objects, CollisionCheckDebugMap & object_debug) + const ExtendedPredictedObjects & target_objects, CollisionCheckDebugMap & object_debug) { - const auto route_handler = *common_data_ptr->route_handler_ptr; - const auto lane_change_parameters = *common_data_ptr->lc_param_ptr; - const auto & object_check_min_road_shoulder_width = - lane_change_parameters.object_check_min_road_shoulder_width; - const auto & object_shiftable_ratio_threshold = lane_change_parameters.th_object_shiftable_ratio; const auto & current_lane_path = common_data_ptr->current_lanes_path; + const auto & delay_lc_param = common_data_ptr->lc_param_ptr->delay; - if (objects.empty() || lane_change_path.path.points.empty() || current_lane_path.points.empty()) { - return true; - } - - const auto leading_obj_idx = getLeadingStaticObjectIdx( - route_handler, lane_change_path, objects, object_check_min_road_shoulder_width, - object_shiftable_ratio_threshold); - if (!leading_obj_idx) { - return true; - } - - const auto & leading_obj = objects.at(*leading_obj_idx); - auto debug = utils::path_safety_checker::createObjectDebug(leading_obj); - const auto leading_obj_poly = - autoware::universe_utils::toPolygon2d(leading_obj.initial_pose, leading_obj.shape); - if (leading_obj_poly.outer().empty()) { - return true; + if ( + !delay_lc_param.enable || target_objects.empty() || lane_change_path.path.points.empty() || + current_lane_path.points.empty()) { + return false; } - const auto & current_path_end = current_lane_path.points.back().point.pose.position; - const auto dist_to_path_end = [&](const auto & src_point) { - if (common_data_ptr->lanes_ptr->current_lane_in_goal_section) { - const auto goal_pose = route_handler.getGoalPose(); - return motion_utils::calcSignedArcLength( - current_lane_path.points, src_point, goal_pose.position); - } - return motion_utils::calcSignedArcLength(current_lane_path.points, src_point, current_path_end); + const auto dist_to_end = common_data_ptr->transient_data.dist_to_terminal_end; + const auto dist_buffer = common_data_ptr->transient_data.current_dist_buffer.min; + auto is_near_end = [&dist_to_end, &dist_buffer](const ExtendedPredictedObject & obj) { + const auto dist_obj_to_end = dist_to_end - obj.dist_from_ego; + return dist_obj_to_end <= dist_buffer; }; - const auto min_dist_to_end_of_current_lane = std::invoke([&]() { - auto min_dist_to_end_of_current_lane = std::numeric_limits::max(); - for (const auto & point : leading_obj_poly.outer()) { - const auto obj_p = universe_utils::createPoint(point.x(), point.y(), 0.0); - const auto dist = dist_to_path_end(obj_p); - min_dist_to_end_of_current_lane = std::min(dist, min_dist_to_end_of_current_lane); - } - return min_dist_to_end_of_current_lane; - }); - - // If there are still enough length after the target object, we delay the lane change - if (min_dist_to_end_of_current_lane <= common_data_ptr->transient_data.current_dist_buffer.min) { - return true; - } - - const auto current_pose = common_data_ptr->get_ego_pose(); - const auto dist_ego_to_obj = motion_utils::calcSignedArcLength( - current_lane_path.points, current_pose.position, leading_obj.initial_pose.position); - - if (dist_ego_to_obj < lane_change_path.info.length.lane_changing) { - return true; - } - - debug.second.unsafe_reason = "delay lane change"; - utils::path_safety_checker::updateCollisionCheckDebugMap(object_debug, debug, false); - return false; -} - -std::optional getLeadingStaticObjectIdx( - const RouteHandler & route_handler, const LaneChangePath & lane_change_path, - const std::vector & objects, - const double object_check_min_road_shoulder_width, const double object_shiftable_ratio_threshold) -{ - const auto & path = lane_change_path.path; - - if (path.points.empty() || objects.empty()) { - return {}; - } - - const auto & lane_change_start = lane_change_path.info.lane_changing_start; - const auto & path_end = path.points.back(); - - double dist_lc_start_to_leading_obj = 0.0; - std::optional leading_obj_idx = std::nullopt; - for (size_t obj_idx = 0; obj_idx < objects.size(); ++obj_idx) { - const auto & obj = objects.at(obj_idx); - const auto & obj_pose = obj.initial_pose; - - // ignore non-static object - // TODO(shimizu): parametrize threshold - const double obj_vel_norm = std::hypot(obj.initial_twist.linear.x, obj.initial_twist.linear.y); - if (obj_vel_norm > 1.0) { - continue; - } + const auto ego_vel = common_data_ptr->get_ego_speed(); + const auto min_lon_acc = common_data_ptr->lc_param_ptr->trajectory.min_longitudinal_acc; + const auto gap_threshold = std::abs((ego_vel * ego_vel) / (2 * min_lon_acc)); + auto is_sufficient_gap = [&gap_threshold](const auto & current_obj, const auto & next_obj) { + const auto curr_obj_half_length = current_obj.shape.dimensions.x; + const auto next_obj_half_length = next_obj.shape.dimensions.x; + const auto dist_current_to_next = next_obj.dist_from_ego - current_obj.dist_from_ego; + const auto gap_length = dist_current_to_next - curr_obj_half_length - next_obj_half_length; + return gap_length > gap_threshold; + }; - // ignore non-parked object - if (!isParkedObject( - path, route_handler, obj, object_check_min_road_shoulder_width, - object_shiftable_ratio_threshold)) { - continue; - } + for (auto it = target_objects.begin(); it < target_objects.end(); ++it) { + if (is_near_end(*it)) break; - const double dist_back_to_obj = autoware::motion_utils::calcSignedArcLength( - path.points, path_end.point.pose.position, obj_pose.position); - if (dist_back_to_obj > 0.0) { - // object is not on the lane change path - continue; - } + if (it->dist_from_ego < lane_change_path.info.length.lane_changing) continue; - const double dist_lc_start_to_obj = autoware::motion_utils::calcSignedArcLength( - path.points, lane_change_start.position, obj_pose.position); - if (dist_lc_start_to_obj < 0.0) { - // object is on the lane changing path or behind it. It will be detected in safety check + if ( + delay_lc_param.check_only_parked_vehicle && + !isParkedObject( + lane_change_path.path, *common_data_ptr->route_handler_ptr, *it, + delay_lc_param.min_road_shoulder_width, delay_lc_param.th_parked_vehicle_shift_ratio)) { continue; } - if (dist_lc_start_to_obj > dist_lc_start_to_leading_obj) { - dist_lc_start_to_leading_obj = dist_lc_start_to_obj; - leading_obj_idx = obj_idx; + auto next_it = std::next(it); + if (next_it == target_objects.end() || is_sufficient_gap(*it, *next_it)) { + auto debug = utils::path_safety_checker::createObjectDebug(*it); + debug.second.unsafe_reason = "delay lane change"; + utils::path_safety_checker::updateCollisionCheckDebugMap(object_debug, debug, false); + return true; } } - return leading_obj_idx; + return false; } lanelet::BasicPolygon2d create_polygon( From d3f3f65c0e79e9e7baf406ad201b87ec5a228bc6 Mon Sep 17 00:00:00 2001 From: Motz Date: Thu, 28 Nov 2024 13:09:07 +0900 Subject: [PATCH 150/273] chore(localization_evaluator): Add some maintainers (#9503) Signed-off-by: Motsu-san --- evaluator/localization_evaluator/package.xml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/evaluator/localization_evaluator/package.xml b/evaluator/localization_evaluator/package.xml index 49dd156f983b4..b9d6285a0f08c 100644 --- a/evaluator/localization_evaluator/package.xml +++ b/evaluator/localization_evaluator/package.xml @@ -6,6 +6,11 @@ Dominik Jargot Koji Minoda + Anh Nguyen + Masahiro Sakamoto + Shintaro Sakoda + Taiki Yamada + Yamato Ando Apache License 2.0 From b9dae3f171848645d53f50415c5e9d655c183326 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 28 Nov 2024 04:30:46 +0000 Subject: [PATCH 151/273] chore: update CODEOWNERS (#9366) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index df6be468e726f..6ac99a0243921 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -24,8 +24,9 @@ common/autoware_signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.j common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp common/autoware_testing/** adam.dabrowski@robotec.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_time_utils/** christopherj.ho@gmail.com shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -common/autoware_trajectory/** mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yukinari.hisaki.2@tier4.jp +common/autoware_traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp common/autoware_traffic_light_utils/** kotaro.uetake@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp +common/autoware_trajectory/** mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yukinari.hisaki.2@tier4.jp common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp @@ -41,17 +42,16 @@ common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp khal common/tier4_system_rviz_plugin/** koji.minoda@tier4.jp common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp -common/traffic_light_recognition_marker_publisher/** shumpei.wakabayashi@tier4.jp takeshi.miura@tier4.jp tomoya.kimura@tier4.jp control/autoware_autonomous_emergency_braking/** daniel.sanchez@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/autoware_collision_detector/** go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp tomohito.ando@tier4.jp control/autoware_control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_joy_controller/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_lane_departure_checker/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp zulfaqar.azmi@tier4.jp -control/autoware_mpc_lateral_controller/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +control/autoware_mpc_lateral_controller/** kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_obstacle_collision_checker/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp control/autoware_operation_mode_transition_manager/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -control/autoware_pid_longitudinal_controller/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp +control/autoware_pid_longitudinal_controller/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp control/autoware_pure_pursuit/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_shift_decider/** takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_smart_mpc_trajectory_follower/** kosuke.takeuchi@tier4.jp masayuki.aino@proxima-ai-tech.com takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp @@ -63,7 +63,7 @@ control/predicted_path_checker/** berkay@leodrive.ai evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp temkei.kem@tier4.jp evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp temkei.kem@tier4.jp evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp -evaluator/localization_evaluator/** dominik.jargot@robotec.ai koji.minoda@tier4.jp +evaluator/localization_evaluator/** anh.nguyen.2@tier4.jp dominik.jargot@robotec.ai koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp evaluator/perception_online_evaluator/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp evaluator/scenario_simulator_v2_adapter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp launch/tier4_autoware_api_launch/** isamu.takagi@tier4.jp ryohsuke.mitsudome@tier4.jp @@ -97,14 +97,14 @@ localization/yabloc/yabloc_image_processing/** anh.nguyen.2@tier4.jp kento.yabuu 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 localization/yabloc/yabloc_particle_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/yabloc/yabloc_pose_initializer/** 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 -map/autoware_lanelet2_map_visualizer/** 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 +map/autoware_lanelet2_map_visualizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp mamoru.sobue@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp map/autoware_map_height_fitter/** 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 +map/autoware_map_loader/** 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 map/autoware_map_projection_loader/** 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 map/autoware_map_tf_generator/** 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 -map/map_loader/** 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 perception/autoware_bytetrack/** manato.hirabayashi@tier4.jp yoshi.ri@tier4.jp perception/autoware_cluster_merger/** dai.nguyen@tier4.jp shunsuke.miura@tier4.jp yukihiro.saito@tier4.jp -perception/autoware_compare_map_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp yukihiro.saito@tier4.jp +perception/autoware_compare_map_segmentation/** abrahammonrroy@yahoo.com dai.nguyen@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp perception/autoware_crosswalk_traffic_light_estimator/** masato.saeki@tier4.jp satoshi.ota@tier4.jp shunsuke.miura@tier4.jp tao.zhong@tier4.jp perception/autoware_detected_object_feature_remover/** kotaro.uetake@tier4.jp tomoya.kimura@tier4.jp yoshi.ri@tier4.jp perception/autoware_detected_object_validation/** dai.nguyen@tier4.jp shintaro.tomie@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp yukihiro.saito@tier4.jp @@ -169,7 +169,7 @@ planning/behavior_path_planner/autoware_behavior_path_external_request_lane_chan planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_planner/autoware_behavior_path_lane_change_module/** alqudah.mohammad@tier4.jp fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner/autoware_behavior_path_planner/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_path_planner/autoware_behavior_path_planner_common/** daniel.sanchez@tier4.jp fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_planner/autoware_behavior_path_planner_common/** alqudah.mohammad@tier4.jp daniel.sanchez@tier4.jp fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/** daniel.sanchez@tier4.jp maxime.clement@tier4.jp planning/behavior_path_planner/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_planner/autoware_behavior_path_start_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp @@ -185,7 +185,7 @@ planning/behavior_velocity_planner/autoware_behavior_velocity_planner/** kosuke. planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/** fumiya.watanabe@tier4.jp isamu.takagi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/** kosuke.takeuchi@tier4.jp makoto.kurihara@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/** mdogru@leodrive.ai shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp zhe.shen@tier4.jp +planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp yukinari.hisaki.2@tier4.jp zhe.shen@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/** daniel.sanchez@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/** mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/** kosuke.takeuchi@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @@ -245,5 +245,6 @@ vehicle/autoware_accel_brake_map_calibrator/** eiki.nagata.2@tier4.jp taiki.tana vehicle/autoware_external_cmd_converter/** eiki.nagata.2@tier4.jp takamasa.horibe@tier4.jp vehicle/autoware_raw_vehicle_cmd_converter/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp sho.iwasawa.2@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp +visualization/autoware_pyplot/** mamoru.sobue@tier4.jp yukinari.hisaki.2@tier4.jp ### Copied from .github/CODEOWNERS-manual ### From 89c18006234c70b4bb8cd161d611cba9550dd759 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 13:39:35 +0900 Subject: [PATCH 152/273] fix(autoware_elevation_map_loader): fix clang-diagnostic-format-security (#9492) Signed-off-by: kobayu858 --- .../src/elevation_map_loader_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_elevation_map_loader/src/elevation_map_loader_node.cpp b/perception/autoware_elevation_map_loader/src/elevation_map_loader_node.cpp index 969c287622757..20a19cee4de59 100644 --- a/perception/autoware_elevation_map_loader/src/elevation_map_loader_node.cpp +++ b/perception/autoware_elevation_map_loader/src/elevation_map_loader_node.cpp @@ -148,7 +148,7 @@ void ElevationMapLoaderNode::publish() is_bag_loaded = grid_map::GridMapRosConverter::loadFromBag( *data_manager_.elevation_map_path_, "elevation_map", elevation_map_); } catch (const std::runtime_error & e) { - RCLCPP_ERROR(this->get_logger(), e.what()); + RCLCPP_ERROR(this->get_logger(), "%s", e.what()); is_bag_loaded = false; } if (!is_bag_loaded) { From af8db0c712b300f6a3c78eb1237ec532e8289088 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Thu, 28 Nov 2024 14:12:45 +0900 Subject: [PATCH 153/273] fix(mission_planner): fix initialization after route set (#9457) Signed-off-by: Takagi, Isamu --- .../src/mission_planner/mission_planner.cpp | 32 ++++++++----------- .../src/mission_planner/mission_planner.hpp | 1 + 2 files changed, 15 insertions(+), 18 deletions(-) diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp index 467bc33d20a56..521beb8f7dcd5 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp @@ -81,6 +81,7 @@ MissionPlanner::MissionPlanner(const rclcpp::NodeOptions & options) // otherwise the mission planner rejects the request for the API. const auto period = rclcpp::Rate(10).period(); data_check_timer_ = create_wall_timer(period, [this] { check_initialization(); }); + is_mission_planner_ready_ = false; logger_configure_ = std::make_unique(this); pub_processing_time_ = @@ -122,6 +123,7 @@ void MissionPlanner::check_initialization() } // All data is ready. Now API is available. + is_mission_planner_ready_ = true; RCLCPP_DEBUG(logger, "Route API is ready."); change_state(RouteState::UNSET); @@ -185,12 +187,8 @@ void MissionPlanner::on_modified_goal(const PoseWithUuidStamped::ConstSharedPtr RCLCPP_ERROR(get_logger(), "The route hasn't set yet. Cannot reroute."); return; } - if (!planner_->ready()) { - RCLCPP_ERROR(get_logger(), "The planner is not ready."); - return; - } - if (!odometry_) { - RCLCPP_ERROR(get_logger(), "The vehicle pose is not received."); + if (!is_mission_planner_ready_) { + RCLCPP_ERROR(get_logger(), "The mission planner is not ready."); return; } if (!current_route_) { @@ -220,6 +218,12 @@ void MissionPlanner::on_modified_goal(const PoseWithUuidStamped::ConstSharedPtr void MissionPlanner::on_clear_route( const ClearRoute::Request::SharedPtr, const ClearRoute::Response::SharedPtr res) { + if (!is_mission_planner_ready_) { + using ResponseCode = autoware_adapi_v1_msgs::msg::ResponseStatus; + throw service_utils::ServiceException( + ResponseCode::NO_EFFECT, "The mission planner is not ready.", true); + } + change_route(); change_state(RouteState::UNSET); res->status.success = true; @@ -235,13 +239,9 @@ void MissionPlanner::on_set_lanelet_route( throw service_utils::ServiceException( ResponseCode::ERROR_INVALID_STATE, "The route cannot be set in the current state."); } - if (!planner_->ready()) { + if (!is_mission_planner_ready_) { throw service_utils::ServiceException( - ResponseCode::ERROR_PLANNER_UNREADY, "The planner is not ready."); - } - if (!odometry_) { - throw service_utils::ServiceException( - ResponseCode::ERROR_PLANNER_UNREADY, "The vehicle pose is not received."); + ResponseCode::ERROR_PLANNER_UNREADY, "The mission planner is not ready."); } if (is_reroute && !operation_mode_state_) { throw service_utils::ServiceException( @@ -302,13 +302,9 @@ void MissionPlanner::on_set_waypoint_route( throw service_utils::ServiceException( ResponseCode::ERROR_INVALID_STATE, "The route cannot be set in the current state."); } - if (!planner_->ready()) { - throw service_utils::ServiceException( - ResponseCode::ERROR_PLANNER_UNREADY, "The planner is not ready."); - } - if (!odometry_) { + if (!is_mission_planner_ready_) { throw service_utils::ServiceException( - ResponseCode::ERROR_PLANNER_UNREADY, "The vehicle pose is not received."); + ResponseCode::ERROR_PLANNER_UNREADY, "The mission planner is not ready."); } if (is_reroute && !operation_mode_state_) { throw service_utils::ServiceException( diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp index b0389c49bef33..987ca6482ec11 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.hpp @@ -136,6 +136,7 @@ class MissionPlanner : public rclcpp::Node rclcpp::TimerBase::SharedPtr data_check_timer_; void check_initialization(); + bool is_mission_planner_ready_; double reroute_time_threshold_; double minimum_reroute_length_; From 562a49d63a8a581ffaa8e5a8967a896ad7381ca7 Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Thu, 28 Nov 2024 14:53:32 +0900 Subject: [PATCH 154/273] feat(autoware_lidar_centerpoint): added a check to notify if we are dropping pillars (#9488) * feat: added a check to notify if we are dropping pillars Signed-off-by: Kenzo Lobos-Tsunekawa * chore: updated text Signed-off-by: Kenzo Lobos-Tsunekawa * chore: throttled the message Signed-off-by: Kenzo Lobos-Tsunekawa --------- Signed-off-by: Kenzo Lobos-Tsunekawa --- .../lib/centerpoint_trt.cpp | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp index 5f81b70ab6d15..6ee2b3733bdb0 100644 --- a/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp +++ b/perception/autoware_lidar_centerpoint/lib/centerpoint_trt.cpp @@ -135,8 +135,7 @@ bool CenterPointTRT::detect( cudaMemsetAsync(spatial_features_d_.get(), 0, spatial_features_size_ * sizeof(float), stream_)); if (!preprocess(input_pointcloud_msg, tf_buffer)) { - RCLCPP_WARN_STREAM( - rclcpp::get_logger("lidar_centerpoint"), "Fail to preprocess and skip to detect."); + RCLCPP_WARN(rclcpp::get_logger("lidar_centerpoint"), "Fail to preprocess and skip to detect."); return false; } @@ -144,6 +143,20 @@ bool CenterPointTRT::detect( postProcess(det_boxes3d); + // Check the actual number of pillars after inference to avoid unnecessary synchronization. + unsigned int num_pillars = 0; + CHECK_CUDA_ERROR( + cudaMemcpy(&num_pillars, num_voxels_d_.get(), sizeof(unsigned int), cudaMemcpyDeviceToHost)); + + if (num_pillars >= config_.max_voxel_size_) { + rclcpp::Clock clock{RCL_ROS_TIME}; + RCLCPP_WARN_THROTTLE( + rclcpp::get_logger("lidar_centerpoint"), clock, 1000, + "The actual number of pillars (%u) exceeds its maximum value (%zu). " + "Please considering increasing it since it may limit the detection performance.", + num_pillars, config_.max_voxel_size_); + } + return true; } From ecdb3f5db2d10b92bba747c08816f1b815b74559 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 15:25:40 +0900 Subject: [PATCH 155/273] fix(autoware_tensorrt_common): fix clang-diagnostic-unused-private-field (#9493) Signed-off-by: kobayu858 --- .../include/autoware/tensorrt_common/tensorrt_common.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp index 6fb90d1415244..76a9fd8bab7a8 100644 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp @@ -222,8 +222,6 @@ class TrtCommon // NOLINT TrtUniquePtr context_; std::unique_ptr calibrator_; - nvinfer1::Dims input_dims_; - nvinfer1::Dims output_dims_; std::string precision_; BatchConfig batch_config_; size_t max_workspace_size_; From 710dacc4e7ba14b9c037a215a9408950f545cd21 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 28 Nov 2024 15:29:47 +0900 Subject: [PATCH 156/273] refactor(autoware_autonomous_emergency_braking): add getObjectOnPathData and getLongitudinalOffset functions (#9462) * feat(aeb): add getObjectOnPathData and getLongitudinalOffset functions Signed-off-by: kyoichi-sugahara --------- Signed-off-by: Kyoichi Sugahara --- .../autonomous_emergency_braking/utils.hpp | 23 ++++++ .../src/node.cpp | 66 +++++----------- .../src/utils.cpp | 50 +++++++++++++ .../test/test.cpp | 75 ++++++++++++++++++- 4 files changed, 166 insertions(+), 48 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp index 18f3716b755ee..3b1994481c8b1 100644 --- a/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp +++ b/control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp @@ -15,9 +15,12 @@ #ifndef AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_ #define AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_ +#include "autoware/autonomous_emergency_braking/node.hpp" + #include #include +#include #include #include @@ -49,6 +52,26 @@ using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; +/** + * @brief Get the Object data of an obstacle inside the ego path + * @param path the ego path + * @param front_offset offset from ego baselink to front + * @param rear_offset offset from ego baselink to back + */ +std::optional getObjectOnPathData( + const std::vector & ego_path, const geometry_msgs::msg::Point & obj_position, + const rclcpp::Time & stamp, const double path_length, const double path_width, + const double path_expansion, const double longitudinal_offset, const double object_speed = 0.0); + +/** + * @brief Get the longitudinal offset based on vehicle traveling direction + * @param path the ego path + * @param front_offset offset from ego baselink to front + * @param rear_offset offset from ego baselink to back + */ +std::optional getLongitudinalOffset( + const std::vector & path, const double front_offset, const double rear_offset); + /** * @brief Apply a transform to a predicted object * @param input the predicted object diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 7c4cf58cbc6e7..7d019023b1656 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -815,6 +815,13 @@ void AEB::createObjectDataUsingPredictedObjects( const auto transform_stamped_opt = utils::getTransform("base_link", predicted_objects_ptr_->header.frame_id, tf_buffer_, logger); if (!transform_stamped_opt.has_value()) return; + + const auto longitudinal_offset_opt = utils::getLongitudinalOffset( + ego_path, vehicle_info_.max_longitudinal_offset_m, vehicle_info_.rear_overhang_m); + + if (!longitudinal_offset_opt.has_value()) return; + const auto longitudinal_offset = longitudinal_offset_opt.value(); + // Check which objects collide with the ego footprints std::for_each(objects.begin(), objects.end(), [&](const auto & predicted_object) { // get objects in base_link frame @@ -842,10 +849,7 @@ void AEB::createObjectDataUsingPredictedObjects( // If the object is behind the ego, we need to use the backward long offset. The // distance should be a positive number in any case - const bool is_object_in_front_of_ego = obj_arc_length > 0.0; - const double dist_ego_to_object = - (is_object_in_front_of_ego) ? obj_arc_length - vehicle_info_.max_longitudinal_offset_m - : obj_arc_length + vehicle_info_.min_longitudinal_offset_m; + const double dist_ego_to_object = obj_arc_length - longitudinal_offset; ObjectData obj; obj.stamp = stamp; @@ -928,53 +932,21 @@ void AEB::getClosestObjectsOnPath( if (ego_path.size() < 2 || points_belonging_to_cluster_hulls->empty()) { return; } - const auto ego_is_driving_forward_opt = autoware::motion_utils::isDrivingForward(ego_path); - if (!ego_is_driving_forward_opt.has_value()) { - return; - } - const bool ego_is_driving_forward = ego_is_driving_forward_opt.value(); - // select points inside the ego footprint path - const auto current_p = [&]() { - const auto & first_point_of_path = ego_path.front(); - const auto & p = first_point_of_path.position; - return autoware::universe_utils::createPoint(p.x, p.y, p.z); - }(); + const auto longitudinal_offset_opt = utils::getLongitudinalOffset( + ego_path, vehicle_info_.max_longitudinal_offset_m, vehicle_info_.rear_overhang_m); + + if (!longitudinal_offset_opt.has_value()) return; + const auto longitudinal_offset = longitudinal_offset_opt.value(); const auto path_length = autoware::motion_utils::calcArcLength(ego_path); + const auto path_width = vehicle_info_.vehicle_width_m / 2.0 + expand_width_; + // select points inside the ego footprint path for (const auto & p : *points_belonging_to_cluster_hulls) { const auto obj_position = autoware::universe_utils::createPoint(p.x, p.y, p.z); - const double obj_arc_length = - autoware::motion_utils::calcSignedArcLength(ego_path, current_p, obj_position); - if ( - std::isnan(obj_arc_length) || - obj_arc_length > path_length + vehicle_info_.max_longitudinal_offset_m) - continue; - - // calculate the lateral offset between the ego vehicle and the object - const double lateral_offset = - std::abs(autoware::motion_utils::calcLateralOffset(ego_path, obj_position)); - - if (std::isnan(lateral_offset)) continue; - - // object is outside region of interest - if ( - lateral_offset > - vehicle_info_.vehicle_width_m / 2.0 + expand_width_ + speed_calculation_expansion_margin_) { - continue; - } - - // If the object is behind the ego, we need to use the backward long offset. The distance should - // be a positive number in any case - const double dist_ego_to_object = (ego_is_driving_forward) - ? obj_arc_length - vehicle_info_.max_longitudinal_offset_m - : obj_arc_length + vehicle_info_.min_longitudinal_offset_m; - ObjectData obj; - obj.stamp = stamp; - obj.position = obj_position; - obj.velocity = 0.0; - obj.distance_to_object = std::abs(dist_ego_to_object); - obj.is_target = (lateral_offset < vehicle_info_.vehicle_width_m / 2.0 + expand_width_); - objects.push_back(obj); + auto obj_data_opt = utils::getObjectOnPathData( + ego_path, obj_position, stamp, path_length, path_width, speed_calculation_expansion_margin_, + longitudinal_offset, 0.0); + if (obj_data_opt.has_value()) objects.push_back(obj_data_opt.value()); } } diff --git a/control/autoware_autonomous_emergency_braking/src/utils.cpp b/control/autoware_autonomous_emergency_braking/src/utils.cpp index 5d9782ada5fbd..9b9d09777e09e 100644 --- a/control/autoware_autonomous_emergency_braking/src/utils.cpp +++ b/control/autoware_autonomous_emergency_braking/src/utils.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include +#include #include #include @@ -27,6 +28,55 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; using geometry_msgs::msg::Vector3; +std::optional getObjectOnPathData( + const std::vector & ego_path, const geometry_msgs::msg::Point & obj_position, + const rclcpp::Time & stamp, const double path_length, const double path_width, + const double path_expansion, const double longitudinal_offset, const double object_speed) +{ + const auto current_p = [&]() { + const auto & p = ego_path.front().position; + return autoware::universe_utils::createPoint(p.x, p.y, p.z); + }(); + const double obj_arc_length = + autoware::motion_utils::calcSignedArcLength(ego_path, current_p, obj_position); + if ( + std::isnan(obj_arc_length) || obj_arc_length < 0.0 || + obj_arc_length > path_length + longitudinal_offset) { + return {}; + } + + // calculate the lateral offset between the ego vehicle and the object + const double lateral_offset = + std::abs(autoware::motion_utils::calcLateralOffset(ego_path, obj_position)); + + // object is outside region of interest + if (std::isnan(lateral_offset) || lateral_offset > path_width + path_expansion) { + return {}; + } + + // If the object is behind the ego, we need to use the backward long offset. The distance should + // be a positive number in any case + const double dist_ego_to_object = obj_arc_length - longitudinal_offset; + ObjectData obj; + obj.stamp = stamp; + obj.position = obj_position; + obj.velocity = object_speed; + obj.distance_to_object = std::abs(dist_ego_to_object); + obj.is_target = (lateral_offset < path_width); + return obj; +} + +std::optional getLongitudinalOffset( + const std::vector & ego_path, const double front_offset, const double rear_offset) +{ + const auto ego_is_driving_forward_opt = autoware::motion_utils::isDrivingForward(ego_path); + if (!ego_is_driving_forward_opt.has_value()) { + return {}; + } + const bool ego_is_driving_forward = ego_is_driving_forward_opt.value(); + return (ego_is_driving_forward) ? front_offset : rear_offset; +} + PredictedObject transformObjectFrame( const PredictedObject & input, const geometry_msgs::msg::TransformStamped & transform_stamped) { diff --git a/control/autoware_autonomous_emergency_braking/test/test.cpp b/control/autoware_autonomous_emergency_braking/test/test.cpp index 3c00a4e6b5caf..360e6f9877e06 100644 --- a/control/autoware_autonomous_emergency_braking/test/test.cpp +++ b/control/autoware_autonomous_emergency_braking/test/test.cpp @@ -21,12 +21,14 @@ #include #include +#include #include #include #include #include +#include #include #include @@ -126,6 +128,76 @@ TEST_F(TestAEB, checkCollision) ASSERT_FALSE(aeb_node_->hasCollision(longitudinal_velocity, object_no_collision)); } +TEST_F(TestAEB, getObjectOnPathData) +{ + constexpr double longitudinal_velocity = 3.0; + constexpr double yaw_rate = 0.0; + const auto imu_path = aeb_node_->generateEgoPath(longitudinal_velocity, yaw_rate); + ASSERT_FALSE(imu_path.empty()); + + const double path_width = 2.0; + const auto path_length = autoware::motion_utils::calcArcLength(imu_path); + ASSERT_TRUE( + path_length < aeb_node_->max_generated_imu_path_length_ + + aeb_node_->imu_prediction_time_interval_ * longitudinal_velocity + + std::numeric_limits::epsilon()); + + const auto stamp = rclcpp::Time(); + + const auto longitudinal_offset_opt = utils::getLongitudinalOffset(imu_path, 1.0, -1.0); + ASSERT_TRUE(longitudinal_offset_opt.has_value()); + const auto longitudinal_offset = longitudinal_offset_opt.value(); + ASSERT_DOUBLE_EQ(longitudinal_offset, 1.0); + + // Object in path if longitudinal_offset is considered + Point obj_position; + double path_expansion; + + { + obj_position.x = path_length + std::numeric_limits::epsilon(); + obj_position.y = 1.0; + path_expansion = 0.0; + auto obj_data_opt = utils::getObjectOnPathData( + imu_path, obj_position, stamp, path_length, path_width, path_expansion, longitudinal_offset, + 0.0); + ASSERT_TRUE(obj_data_opt.has_value()); + ASSERT_TRUE(obj_data_opt.value().is_target); + } + + // Object outside of path + { + obj_position.x = path_length + std::numeric_limits::epsilon(); + obj_position.y = 3.0; + path_expansion = 0.0; + auto obj_data_opt = utils::getObjectOnPathData( + imu_path, obj_position, stamp, path_length, path_width, path_expansion, longitudinal_offset, + 0.0); + ASSERT_FALSE(obj_data_opt.has_value()); + } + + // Object outside of path + { + obj_position.x = -1.0; + obj_position.y = 0.0; + path_expansion = 0.0; + auto obj_data_opt = utils::getObjectOnPathData( + imu_path, obj_position, stamp, path_length, path_width, path_expansion, longitudinal_offset, + 0.0); + ASSERT_FALSE(obj_data_opt.has_value()); + } + + // Object is covered by path expansion + { + obj_position.x = path_length + std::numeric_limits::epsilon(); + obj_position.y = 3.0; + path_expansion = 2.0; + auto obj_data_opt = utils::getObjectOnPathData( + imu_path, obj_position, stamp, path_length, path_width, 2.0, longitudinal_offset, 0.0); + ASSERT_TRUE(obj_data_opt.has_value()); + ASSERT_FALSE(obj_data_opt.value().is_target); + } +} + TEST_F(TestAEB, checkImuPathGeneration) { constexpr double longitudinal_velocity = 3.0; @@ -145,7 +217,7 @@ TEST_F(TestAEB, checkImuPathGeneration) pcl::PointCloud::Ptr obstacle_points_ptr = pcl::make_shared>(); { - const double x_start{0.0}; + const double x_start{0.5}; const double y_start{0.0}; for (size_t i = 0; i < 15; ++i) { @@ -162,6 +234,7 @@ TEST_F(TestAEB, checkImuPathGeneration) MarkerArray debug_markers; aeb_node_->getPointsBelongingToClusterHulls( obstacle_points_ptr, points_belonging_to_cluster_hulls, debug_markers); + ASSERT_FALSE(points_belonging_to_cluster_hulls->empty()); std::vector objects; aeb_node_->getClosestObjectsOnPath(imu_path, stamp, points_belonging_to_cluster_hulls, objects); ASSERT_FALSE(objects.empty()); From 659b6b3836406bc33f257798c1ae41374a72c501 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 28 Nov 2024 15:33:11 +0900 Subject: [PATCH 157/273] refactor(autoware_autonomous_emergency_braking): update longitudinal offset parameter name (#9463) Update the parameter name for the longitudinal offset distance used for collision check in the autonomous emergency braking control module. The parameter name has been changed from "longitudinal_offset" to "longitudinal_offset_margin" to better reflect its purpose. Signed-off-by: kyoichi-sugahara --- .../README.md | 2 +- .../autonomous_emergency_braking.param.yaml | 3 +- .../autonomous_emergency_braking/node.hpp | 3 +- .../src/node.cpp | 43 +++++++++++-------- 4 files changed, 31 insertions(+), 20 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/README.md b/control/autoware_autonomous_emergency_braking/README.md index d3ee7d4e1aa29..7133e4ea6b7f7 100644 --- a/control/autoware_autonomous_emergency_braking/README.md +++ b/control/autoware_autonomous_emergency_braking/README.md @@ -308,7 +308,7 @@ When vehicle odometry information is faulty, it is possible that the MPC fails t | min_generated_imu_path_length | [m] | double | minimum distance for a predicted path generated by sensors | 0.5 | | max_generated_imu_path_length | [m] | double | maximum distance for a predicted path generated by sensors | 10.0 | | expand_width | [m] | double | expansion width of the ego vehicle for collision checking, path cropping and speed calculation | 0.1 | -| longitudinal_offset | [m] | double | longitudinal offset distance for collision check | 2.0 | +| longitudinal_offset_margin | [m] | double | longitudinal offset distance for collision check | 2.0 | | t_response | [s] | double | response time for the ego to detect the front vehicle starting deceleration | 1.0 | | a_ego_min | [m/ss] | double | maximum deceleration value of the ego vehicle | -3.0 | | a_obj_min | [m/ss] | double | maximum deceleration value of objects | -3.0 | 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 99ca4d4ef52cb..b23c3bbdd4d59 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 @@ -4,6 +4,7 @@ use_predicted_trajectory: true use_imu_path: true limit_imu_path_lat_dev: false + limit_imu_path_length: true use_pointcloud_data: true use_predicted_object_data: false use_object_velocity_calculation: true @@ -39,7 +40,7 @@ maximum_cluster_size: 10000 # RSS distance collision check - longitudinal_offset: 1.0 + longitudinal_offset_margin: 1.0 t_response: 1.0 a_ego_min: -3.0 a_obj_min: -1.0 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 96efb5dc9ff1f..3de8a52c70643 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 @@ -556,6 +556,7 @@ class AEB : public rclcpp::Node bool use_predicted_trajectory_; bool use_imu_path_; bool limit_imu_path_lat_dev_; + bool limit_imu_path_length_; bool use_pointcloud_data_; bool use_predicted_object_data_; bool use_object_velocity_calculation_; @@ -571,7 +572,7 @@ class AEB : public rclcpp::Node double min_generated_imu_path_length_; double max_generated_imu_path_length_; double expand_width_; - double longitudinal_offset_; + double longitudinal_offset_margin_; double t_response_; double a_ego_min_; double a_obj_min_; diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 7d019023b1656..21a690cd0eec3 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -57,6 +57,16 @@ #include #endif +namespace +{ +using autoware::motion::control::autonomous_emergency_braking::colorTuple; +constexpr double MIN_MOVING_VELOCITY_THRESHOLD = 0.1; +// Sky blue (RGB: 0, 148, 205) - A medium-bright blue color +constexpr colorTuple IMU_PATH_COLOR = {0.0 / 256.0, 148.0 / 256.0, 205.0 / 256.0, 0.999}; +// Forest green (RGB: 0, 100, 0) - A deep, dark green color +constexpr colorTuple MPC_PATH_COLOR = {0.0 / 256.0, 100.0 / 256.0, 0.0 / 256.0, 0.999}; +} // namespace + namespace autoware::motion::control::autonomous_emergency_braking { using autoware::motion::control::autonomous_emergency_braking::utils::convertObjToPolygon; @@ -156,6 +166,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) use_predicted_trajectory_ = declare_parameter("use_predicted_trajectory"); use_imu_path_ = declare_parameter("use_imu_path"); limit_imu_path_lat_dev_ = declare_parameter("limit_imu_path_lat_dev"); + limit_imu_path_length_ = declare_parameter("limit_imu_path_length"); 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"); @@ -173,7 +184,7 @@ AEB::AEB(const rclcpp::NodeOptions & node_options) min_generated_imu_path_length_ = declare_parameter("min_generated_imu_path_length"); max_generated_imu_path_length_ = declare_parameter("max_generated_imu_path_length"); expand_width_ = declare_parameter("expand_width"); - longitudinal_offset_ = declare_parameter("longitudinal_offset"); + longitudinal_offset_margin_ = declare_parameter("longitudinal_offset_margin"); t_response_ = declare_parameter("t_response"); a_ego_min_ = declare_parameter("a_ego_min"); a_obj_min_ = declare_parameter("a_obj_min"); @@ -220,6 +231,7 @@ rcl_interfaces::msg::SetParametersResult AEB::onParameter( updateParam(parameters, "use_predicted_trajectory", use_predicted_trajectory_); updateParam(parameters, "use_imu_path", use_imu_path_); updateParam(parameters, "limit_imu_path_lat_dev", limit_imu_path_lat_dev_); + updateParam(parameters, "limit_imu_path_length", limit_imu_path_length_); updateParam(parameters, "use_pointcloud_data", use_pointcloud_data_); updateParam(parameters, "use_predicted_object_data", use_predicted_object_data_); updateParam( @@ -238,7 +250,7 @@ rcl_interfaces::msg::SetParametersResult AEB::onParameter( updateParam(parameters, "min_generated_imu_path_length", min_generated_imu_path_length_); updateParam(parameters, "max_generated_imu_path_length", max_generated_imu_path_length_); updateParam(parameters, "expand_width", expand_width_); - updateParam(parameters, "longitudinal_offset", longitudinal_offset_); + updateParam(parameters, "longitudinal_offset_margin", longitudinal_offset_margin_); updateParam(parameters, "t_response", t_response_); updateParam(parameters, "a_ego_min", a_ego_min_); updateParam(parameters, "a_obj_min", a_obj_min_); @@ -460,9 +472,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers) } // step2. create velocity data check if the vehicle stops or not - constexpr double min_moving_velocity_th{0.1}; const double current_v = current_velocity_ptr_->longitudinal_velocity; - if (std::abs(current_v) < min_moving_velocity_th) { + if (std::abs(current_v) < MIN_MOVING_VELOCITY_THRESHOLD) { return false; } @@ -570,18 +581,16 @@ bool AEB::checkCollision(MarkerArray & debug_markers) getPointsBelongingToClusterHulls( filtered_objects, points_belonging_to_cluster_hulls, debug_markers); - const auto imu_path_objects = (!use_imu_path_ || !angular_velocity_ptr_) - ? std::vector{} - : get_objects_on_path( - ego_imu_path, points_belonging_to_cluster_hulls, - {0.0 / 256.0, 148.0 / 256.0, 205.0 / 256.0, 0.999}, "imu"); + const auto imu_path_objects = + (!use_imu_path_ || !angular_velocity_ptr_) + ? std::vector{} + : get_objects_on_path(ego_imu_path, points_belonging_to_cluster_hulls, IMU_PATH_COLOR, "imu"); const auto mpc_path_objects = (!use_predicted_trajectory_ || !predicted_traj_ptr_ || !ego_mpc_path.has_value()) ? std::vector{} : get_objects_on_path( - ego_mpc_path.value(), points_belonging_to_cluster_hulls, - {0.0 / 256.0, 100.0 / 256.0, 0.0 / 256.0, 0.999}, "mpc"); + ego_mpc_path.value(), points_belonging_to_cluster_hulls, MPC_PATH_COLOR, "mpc"); // merge object data which comes from the ego (imu) path and predicted path auto merge_objects = @@ -632,7 +641,7 @@ bool AEB::hasCollision(const double current_v, const ObjectData & closest_object const double obj_braking_distance = (obj_v > 0.0) ? -(obj_v * obj_v) / (2 * std::fabs(a_obj_min_)) : (obj_v * obj_v) / (2 * std::fabs(a_obj_min_)); - return ego_stopping_distance + obj_braking_distance + longitudinal_offset_; + return ego_stopping_distance + obj_braking_distance + longitudinal_offset_margin_; }); tier4_debug_msgs::msg::Float32Stamped rss_distance_msg; @@ -655,10 +664,9 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w) const double & dt = imu_prediction_time_interval_; const double distance_between_points = std::abs(curr_v) * dt; constexpr double minimum_distance_between_points{1e-2}; - // if current velocity is too small, assume it stops at the same point // if distance between points is too small, arc length calculation is unreliable, so we skip // creating the path - if (std::abs(curr_v) < 0.1 || distance_between_points < minimum_distance_between_points) { + if (distance_between_points < minimum_distance_between_points) { return {}; } @@ -700,7 +708,8 @@ Path AEB::generateEgoPath(const double curr_v, const double curr_w) const bool basic_path_conditions_satisfied = (t > horizon) && (path_arc_length > min_generated_imu_path_length_); - const bool path_length_threshold_surpassed = path_arc_length > max_generated_imu_path_length_; + const bool path_length_threshold_surpassed = + limit_imu_path_length_ && path_arc_length > max_generated_imu_path_length_; const bool lat_dev_threshold_surpassed = limit_imu_path_lat_dev_ && std::abs(edge_of_ego_vehicle.y) > imu_path_lat_dev_threshold_; @@ -1073,9 +1082,9 @@ void AEB::addVirtualStopWallMarker(MarkerArray & markers) }); if (ego_map_pose.has_value()) { - const double base_to_front_offset = vehicle_info_.max_longitudinal_offset_m; + const double base_link_to_front_offset = vehicle_info_.max_longitudinal_offset_m; const auto ego_front_pose = autoware::universe_utils::calcOffsetPose( - ego_map_pose.value(), base_to_front_offset, 0.0, 0.0, 0.0); + ego_map_pose.value(), base_link_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, &markers); From 64faa5c255bdaa905b008fdaae0d59aa164fe83d Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 16:11:04 +0900 Subject: [PATCH 158/273] fix(autoware_traffic_light_classifier): fix clang-diagnostic-delete-abstract-non-virtual-dtor (#9497) fix: clang-diagnostic-delete-abstract-non-virtual-dtor Signed-off-by: kobayu858 --- .../src/classifier/classifier_interface.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/perception/autoware_traffic_light_classifier/src/classifier/classifier_interface.hpp b/perception/autoware_traffic_light_classifier/src/classifier/classifier_interface.hpp index cff5828a5b00f..a6b1f8413b1a3 100644 --- a/perception/autoware_traffic_light_classifier/src/classifier/classifier_interface.hpp +++ b/perception/autoware_traffic_light_classifier/src/classifier/classifier_interface.hpp @@ -27,6 +27,7 @@ namespace autoware::traffic_light class ClassifierInterface { public: + virtual ~ClassifierInterface() = default; virtual bool getTrafficSignals( const std::vector & input_image, tier4_perception_msgs::msg::TrafficLightArray & traffic_signals) = 0; From 9d8bd0c0f07c751c3d9973ddf7f13cc48644dff1 Mon Sep 17 00:00:00 2001 From: stevenbrills <90438581+stevenbrills@users.noreply.github.com> Date: Thu, 28 Nov 2024 02:34:41 -0500 Subject: [PATCH 159/273] fix(autoware_freespace_planner, autoware_freespace_planning_algorithms): modify freespace planner to use node clock instead of system clock (#9152) * Modified the autoware_freespace_planner and autoware_freespace_planning_algorithms packages to use the node clock instead of rclcpp detached clock. This allows the module to make use of sim time. Previously during simulation the parking trajectory would have system time in trajectory header messages causing downstream issues like non-clearance of trajectory buffers in motion planning based on elapsed time. * style(pre-commit): autofix * Updated the freespace planner instantiation call in the path planning modules * style(pre-commit): autofix * Updated tests for the utility functions * style(pre-commit): autofix --------- Co-authored-by: Steven Brills Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../autoware/freespace_planner/utils.hpp | 6 ++-- .../freespace_planner_node.cpp | 8 ++--- .../src/autoware_freespace_planner/utils.cpp | 10 +++--- .../test/test_freespace_planner.cpp | 6 ++-- .../test/test_freespace_planner_utils.cpp | 9 +++--- .../abstract_algorithm.hpp | 17 +++++++--- .../astar_search.hpp | 6 +++- .../freespace_planning_algorithms/rrtstar.hpp | 5 +-- .../src/astar_search.cpp | 31 +++++++++++++++++-- .../src/rrtstar.cpp | 15 ++++----- .../test_freespace_planning_algorithms.cpp | 9 ++++-- .../pull_over_planner/freespace_pull_over.cpp | 7 +++-- .../src/freespace_pull_out.cpp | 7 +++-- 13 files changed, 96 insertions(+), 40 deletions(-) diff --git a/planning/autoware_freespace_planner/include/autoware/freespace_planner/utils.hpp b/planning/autoware_freespace_planner/include/autoware/freespace_planner/utils.hpp index 4a7f3b1cd6c2b..1f2347958cfd2 100644 --- a/planning/autoware_freespace_planner/include/autoware/freespace_planner/utils.hpp +++ b/planning/autoware_freespace_planner/include/autoware/freespace_planner/utils.hpp @@ -58,13 +58,15 @@ size_t get_next_target_index( const size_t current_target_index); Trajectory get_partial_trajectory( - const Trajectory & trajectory, const size_t start_index, const size_t end_index); + const Trajectory & trajectory, const size_t start_index, const size_t end_index, + const rclcpp::Clock::SharedPtr clock); Trajectory create_trajectory( const PoseStamped & current_pose, const PlannerWaypoints & planner_waypoints, const double & velocity); -Trajectory create_stop_trajectory(const PoseStamped & current_pose); +Trajectory create_stop_trajectory( + const PoseStamped & current_pose, const rclcpp::Clock::SharedPtr clock); Trajectory create_stop_trajectory(const Trajectory & trajectory); diff --git a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp index f968d668223e0..a937114e653c6 100644 --- a/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/freespace_planner_node.cpp @@ -168,8 +168,8 @@ bool FreespacePlannerNode::checkCurrentTrajectoryCollision() const size_t nearest_index_partial = autoware::motion_utils::findNearestIndex( partial_trajectory_.points, current_pose_.pose.position); const size_t end_index_partial = partial_trajectory_.points.size() - 1; - const auto forward_trajectory = - utils::get_partial_trajectory(partial_trajectory_, nearest_index_partial, end_index_partial); + const auto forward_trajectory = utils::get_partial_trajectory( + partial_trajectory_, nearest_index_partial, end_index_partial, get_clock()); const bool is_obs_found = algo_->hasObstacleOnTrajectory(utils::trajectory_to_pose_array(forward_trajectory)); @@ -316,7 +316,7 @@ void FreespacePlannerNode::onTimer() // stops. if (!is_new_parking_cycle_) { const auto stop_trajectory = partial_trajectory_.points.empty() - ? utils::create_stop_trajectory(current_pose_) + ? utils::create_stop_trajectory(current_pose_, get_clock()) : utils::create_stop_trajectory(partial_trajectory_); trajectory_pub_->publish(stop_trajectory); debug_pose_array_pub_->publish(utils::trajectory_to_pose_array(stop_trajectory)); @@ -352,7 +352,7 @@ void FreespacePlannerNode::onTimer() // Update partial trajectory updateTargetIndex(); partial_trajectory_ = - utils::get_partial_trajectory(trajectory_, prev_target_index_, target_index_); + utils::get_partial_trajectory(trajectory_, prev_target_index_, target_index_, get_clock()); // Publish messages trajectory_pub_->publish(partial_trajectory_); diff --git a/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp index ef22a21d33eb1..2e0c461ae71c0 100644 --- a/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp @@ -87,11 +87,12 @@ size_t get_next_target_index( } Trajectory get_partial_trajectory( - const Trajectory & trajectory, const size_t start_index, const size_t end_index) + const Trajectory & trajectory, const size_t start_index, const size_t end_index, + const rclcpp::Clock::SharedPtr clock) { Trajectory partial_trajectory; partial_trajectory.header = trajectory.header; - partial_trajectory.header.stamp = rclcpp::Clock().now(); + partial_trajectory.header.stamp = clock->now(); partial_trajectory.points.reserve(trajectory.points.size()); for (size_t i = start_index; i <= end_index; ++i) { @@ -134,12 +135,13 @@ Trajectory create_trajectory( return trajectory; } -Trajectory create_stop_trajectory(const PoseStamped & current_pose) +Trajectory create_stop_trajectory( + const PoseStamped & current_pose, const rclcpp::Clock::SharedPtr clock) { PlannerWaypoints waypoints; PlannerWaypoint waypoint; - waypoints.header.stamp = rclcpp::Clock().now(); + waypoints.header.stamp = clock->now(); waypoints.header.frame_id = current_pose.header.frame_id; waypoint.pose.header = waypoints.header; waypoint.pose.pose = current_pose.pose; diff --git a/planning/autoware_freespace_planner/test/test_freespace_planner.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner.cpp index 37ea52c07734b..add449c66eb0d 100644 --- a/planning/autoware_freespace_planner/test/test_freespace_planner.cpp +++ b/planning/autoware_freespace_planner/test/test_freespace_planner.cpp @@ -134,7 +134,8 @@ class TestFreespacePlanner : public ::testing::Test freespace_planner_->reversing_indices_ = reversing_indices; freespace_planner_->partial_trajectory_ = autoware::freespace_planner::utils::get_partial_trajectory( - trajectory_, 0, reversing_indices.front()); + trajectory_, 0, reversing_indices.front(), + std::make_shared(RCL_SYSTEM_TIME)); freespace_planner_->current_pose_.pose = trajectory_.points.front().pose; if (colliding) { @@ -161,7 +162,8 @@ class TestFreespacePlanner : public ::testing::Test trajectory_.points.size(), reversing_indices, freespace_planner_->prev_target_index_); freespace_planner_->partial_trajectory_ = autoware::freespace_planner::utils::get_partial_trajectory( - trajectory_, freespace_planner_->prev_target_index_, freespace_planner_->target_index_); + trajectory_, freespace_planner_->prev_target_index_, freespace_planner_->target_index_, + std::make_shared(RCL_SYSTEM_TIME)); Odometry odom; odom.pose.pose = trajectory_.points.front().pose; diff --git a/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp index 7c795a8eb7b85..534278a3b8dc8 100644 --- a/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp +++ b/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp @@ -229,9 +229,8 @@ TEST(FreespacePlannerUtilsTest, testGetPartialTrajectory) autoware::freespace_planner::utils::get_reversing_indices(trajectory); ASSERT_EQ(reversing_indices.size(), 2ul); - auto partial_traj = autoware::freespace_planner::utils::get_partial_trajectory( - trajectory, 0ul, reversing_indices.front()); + trajectory, 0ul, reversing_indices.front(), std::make_shared(RCL_SYSTEM_TIME)); ASSERT_FALSE(partial_traj.points.empty()); auto expected_size = reversing_indices.front() + 1ul; EXPECT_EQ(partial_traj.points.size(), expected_size); @@ -239,7 +238,8 @@ TEST(FreespacePlannerUtilsTest, testGetPartialTrajectory) EXPECT_FLOAT_EQ(partial_traj.points.back().longitudinal_velocity_mps, 0.0); partial_traj = autoware::freespace_planner::utils::get_partial_trajectory( - trajectory, reversing_indices.front(), reversing_indices.back()); + trajectory, reversing_indices.front(), reversing_indices.back(), + std::make_shared(RCL_SYSTEM_TIME)); ASSERT_FALSE(partial_traj.points.empty()); expected_size = reversing_indices.back() - reversing_indices.front() + 1ul; EXPECT_EQ(partial_traj.points.size(), expected_size); @@ -271,7 +271,8 @@ TEST(FreespacePlannerUtilsTest, testCreateStopTrajectory) geometry_msgs::msg::PoseStamped current_pose; current_pose.pose.position.x = 1.0; - auto stop_traj = autoware::freespace_planner::utils::create_stop_trajectory(current_pose); + auto stop_traj = autoware::freespace_planner::utils::create_stop_trajectory( + current_pose, std::make_shared(RCL_SYSTEM_TIME)); EXPECT_EQ(stop_traj.points.size(), 1ul); if (!stop_traj.points.empty()) { EXPECT_DOUBLE_EQ(stop_traj.points.front().pose.position.x, 1.0); diff --git a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp index 8a4d6bf2e42b5..52b6b404ba6eb 100644 --- a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp @@ -158,8 +158,11 @@ class AbstractPlanningAlgorithm { public: AbstractPlanningAlgorithm( - const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape) - : planner_common_param_(planner_common_param), collision_vehicle_shape_(collision_vehicle_shape) + const PlannerCommonParam & planner_common_param, const rclcpp::Clock::SharedPtr & clock, + const VehicleShape & collision_vehicle_shape) + : planner_common_param_(planner_common_param), + collision_vehicle_shape_(collision_vehicle_shape), + clock_(clock) { planner_common_param_.turning_steps = std::max(planner_common_param_.turning_steps, 1); collision_vehicle_shape_.max_steering *= planner_common_param_.max_turning_ratio; @@ -168,8 +171,11 @@ class AbstractPlanningAlgorithm AbstractPlanningAlgorithm( const PlannerCommonParam & planner_common_param, - const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double margin = 0.0) - : planner_common_param_(planner_common_param), collision_vehicle_shape_(vehicle_info, margin) + const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, + const rclcpp::Clock::SharedPtr & clock, const double margin = 0.0) + : planner_common_param_(planner_common_param), + collision_vehicle_shape_(vehicle_info, margin), + clock_(clock) { planner_common_param_.turning_steps = std::max(planner_common_param_.turning_steps, 1); collision_vehicle_shape_.max_steering *= planner_common_param_.max_turning_ratio; @@ -270,6 +276,9 @@ class AbstractPlanningAlgorithm PlannerCommonParam planner_common_param_; VehicleShape collision_vehicle_shape_; + // Pointer to the parent Node + rclcpp::Clock::SharedPtr clock_; + // costmap as occupancy grid nav_msgs::msg::OccupancyGrid costmap_; 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 65ef53d820cba..cd4ad9d4d6413 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 @@ -98,6 +98,9 @@ class AstarSearch : public AbstractPlanningAlgorithm const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape, const AstarParam & astar_param); + AstarSearch( + const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape, + const AstarParam & astar_param, const rclcpp::Clock::SharedPtr & clock); AstarSearch( const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape, rclcpp::Node & node) @@ -113,7 +116,8 @@ class AstarSearch : public AbstractPlanningAlgorithm node.declare_parameter("astar.distance_heuristic_weight"), node.declare_parameter("astar.smoothness_weight"), node.declare_parameter("astar.obstacle_distance_weight"), - node.declare_parameter("astar.goal_lat_distance_weight")}) + node.declare_parameter("astar.goal_lat_distance_weight")}, + node.get_clock()) { } diff --git a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/rrtstar.hpp b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/rrtstar.hpp index 1bdc7105067d4..8f0ff9a677ebd 100644 --- a/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/rrtstar.hpp +++ b/planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/rrtstar.hpp @@ -39,7 +39,7 @@ class RRTStar : public AbstractPlanningAlgorithm public: RRTStar( const PlannerCommonParam & planner_common_param, const VehicleShape & original_vehicle_shape, - const RRTStarParam & rrtstar_param); + const RRTStarParam & rrtstar_param, const rclcpp::Clock::SharedPtr & clock); RRTStar( const PlannerCommonParam & planner_common_param, const VehicleShape & original_vehicle_shape, @@ -51,7 +51,8 @@ class RRTStar : public AbstractPlanningAlgorithm node.declare_parameter("rrtstar.use_informed_sampling"), node.declare_parameter("rrtstar.max_planning_time"), node.declare_parameter("rrtstar.neighbor_radius"), - node.declare_parameter("rrtstar.margin")}) + node.declare_parameter("rrtstar.margin")}, + node.get_clock()) { } diff --git a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp index 875d44847b40c..3fecf800f1bf6 100644 --- a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp @@ -67,7 +67,34 @@ Pose calcRelativePose(const Pose & base_pose, const Pose & pose) AstarSearch::AstarSearch( const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape, const AstarParam & astar_param) -: AbstractPlanningAlgorithm(planner_common_param, collision_vehicle_shape), +: AbstractPlanningAlgorithm( + planner_common_param, std::make_shared(RCL_ROS_TIME), collision_vehicle_shape), + astar_param_(astar_param), + goal_node_(nullptr), + use_reeds_shepp_(true) +{ + steering_resolution_ = + collision_vehicle_shape_.max_steering / planner_common_param_.turning_steps; + heading_resolution_ = 2.0 * M_PI / planner_common_param_.theta_size; + + const double avg_steering = + steering_resolution_ + (collision_vehicle_shape_.max_steering - steering_resolution_) / 2.0; + avg_turning_radius_ = + kinematic_bicycle_model::getTurningRadius(collision_vehicle_shape_.base_length, avg_steering); + + is_backward_search_ = astar_param_.search_method == "backward"; + + min_expansion_dist_ = astar_param_.expansion_distance; + max_expansion_dist_ = collision_vehicle_shape_.base_length * base_length_max_expansion_factor_; + + near_goal_dist_ = + std::max(astar_param.near_goal_distance, planner_common_param.longitudinal_goal_range); +} + +AstarSearch::AstarSearch( + const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape, + const AstarParam & astar_param, const rclcpp::Clock::SharedPtr & clock) +: AbstractPlanningAlgorithm(planner_common_param, clock, collision_vehicle_shape), astar_param_(astar_param), goal_node_(nullptr), use_reeds_shepp_(true) @@ -399,7 +426,7 @@ double AstarSearch::getLatDistanceCost(const Pose & pose) const void AstarSearch::setPath(const AstarNode & goal_node) { std_msgs::msg::Header header; - header.stamp = rclcpp::Clock(RCL_ROS_TIME).now(); + header.stamp = clock_->now(); header.frame_id = costmap_.header.frame_id; // From the goal node to the start node diff --git a/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp b/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp index 696d04a06cb28..000b118214d9e 100644 --- a/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp @@ -26,13 +26,14 @@ rrtstar_core::Pose poseMsgToPose(const geometry_msgs::msg::Pose & pose_msg) RRTStar::RRTStar( const PlannerCommonParam & planner_common_param, const VehicleShape & original_vehicle_shape, - const RRTStarParam & rrtstar_param) + const RRTStarParam & rrtstar_param, const rclcpp::Clock::SharedPtr & clock) : AbstractPlanningAlgorithm( - planner_common_param, VehicleShape( - original_vehicle_shape.length + 2 * rrtstar_param.margin, - original_vehicle_shape.width + 2 * rrtstar_param.margin, - original_vehicle_shape.base_length, original_vehicle_shape.max_steering, - original_vehicle_shape.base2back + rrtstar_param.margin)), + planner_common_param, clock, + VehicleShape( + original_vehicle_shape.length + 2 * rrtstar_param.margin, + original_vehicle_shape.width + 2 * rrtstar_param.margin, original_vehicle_shape.base_length, + original_vehicle_shape.max_steering, + original_vehicle_shape.base2back + rrtstar_param.margin)), rrtstar_param_(rrtstar_param) { if (rrtstar_param_.margin <= 0) { @@ -129,7 +130,7 @@ bool RRTStar::hasObstacleOnTrajectory(const geometry_msgs::msg::PoseArray & traj void RRTStar::setRRTPath(const std::vector & waypoints) { std_msgs::msg::Header header; - header.stamp = rclcpp::Clock(RCL_ROS_TIME).now(); + header.stamp = clock_->now(); header.frame_id = costmap_.header.frame_id; waypoints_.header = header; diff --git a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp index 2b2254d66c844..a2ed4c3e7e0fc 100644 --- a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp +++ b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp @@ -231,7 +231,9 @@ std::unique_ptr configure_astar(bool use_multi) obstacle_distance_weight, goal_lat_distance_weight}; - auto algo = std::make_unique(planner_common_param, vehicle_shape, astar_param); + auto clock_shrd_ptr = std::make_shared(RCL_ROS_TIME); + auto algo = std::make_unique( + planner_common_param, vehicle_shape, astar_param, clock_shrd_ptr); return algo; } @@ -244,7 +246,10 @@ std::unique_ptr configure_rrtstar(bool informed, const double margin = 0.2; const double max_planning_time = 200; const auto rrtstar_param = fpa::RRTStarParam{update, informed, max_planning_time, mu, margin}; - auto algo = std::make_unique(planner_common_param, vehicle_shape, rrtstar_param); + + auto clock_shrd_ptr = std::make_shared(RCL_ROS_TIME); + auto algo = std::make_unique( + planner_common_param, vehicle_shape, rrtstar_param, clock_shrd_ptr); return algo; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp index 452090571ac45..b51d5df42c75b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp @@ -48,11 +48,12 @@ FreespacePullOver::FreespacePullOver( vehicle_info, parameters.vehicle_shape_margin); if (parameters.freespace_parking_algorithm == "astar") { planner_ = std::make_unique( - parameters.freespace_parking_common_parameters, vehicle_shape, parameters.astar_parameters); + parameters.freespace_parking_common_parameters, vehicle_shape, parameters.astar_parameters, + node.get_clock()); } else if (parameters.freespace_parking_algorithm == "rrtstar") { planner_ = std::make_unique( - parameters.freespace_parking_common_parameters, vehicle_shape, - parameters.rrt_star_parameters); + parameters.freespace_parking_common_parameters, vehicle_shape, parameters.rrt_star_parameters, + node.get_clock()); } } diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp index c3f5e8883c284..f257904e141b6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -38,12 +38,13 @@ FreespacePullOut::FreespacePullOut( if (parameters.freespace_planner_algorithm == "astar") { use_back_ = parameters.astar_parameters.use_back; planner_ = std::make_unique( - parameters.freespace_planner_common_parameters, vehicle_shape, parameters.astar_parameters); + parameters.freespace_planner_common_parameters, vehicle_shape, parameters.astar_parameters, + node.get_clock()); } else if (parameters.freespace_planner_algorithm == "rrtstar") { use_back_ = true; // no option for disabling back in rrtstar planner_ = std::make_unique( - parameters.freespace_planner_common_parameters, vehicle_shape, - parameters.rrt_star_parameters); + parameters.freespace_planner_common_parameters, vehicle_shape, parameters.rrt_star_parameters, + node.get_clock()); } } From 62e9aa877ae9957af6c3c9d6167ba564484ef780 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 16:42:29 +0900 Subject: [PATCH 160/273] fix(autoware_tracking_object_merger): fix clang-diagnostic-sign-conversion (#9507) fix: clang-diagnostic-sign-conversion Signed-off-by: kobayu858 --- .../src/decorative_tracker_merger_node.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp b/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp index 55d31a1b890cd..eab815969ac9a 100644 --- a/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp +++ b/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp @@ -57,7 +57,8 @@ Eigen::MatrixXd calcScoreMatrixForAssociation( const rclcpp::Time current_time = rclcpp::Time(objects0.header.stamp); // calc score matrix - Eigen::MatrixXd score_matrix = Eigen::MatrixXd::Zero(trackers.size(), objects0.objects.size()); + Eigen::MatrixXd score_matrix = Eigen::MatrixXd::Zero( + static_cast(trackers.size()), static_cast(objects0.objects.size())); for (size_t trackers_idx = 0; trackers_idx < trackers.size(); ++trackers_idx) { const auto & tracker_obj = trackers.at(trackers_idx); const auto & object1 = tracker_obj.getObject(); @@ -77,7 +78,8 @@ Eigen::MatrixXd calcScoreMatrixForAssociation( } else { score = data_association_map.at("lidar-radar")->calcScoreBetweenObjects(object0, object1); } - score_matrix(trackers_idx, objects0_idx) = score; + score_matrix( + static_cast(trackers_idx), static_cast(objects0_idx)) = score; } } return score_matrix; @@ -316,9 +318,11 @@ bool DecorativeTrackerMergerNode::decorativeMerger( // look for tracker for (int tracker_idx = 0; tracker_idx < static_cast(inner_tracker_objects_.size()); ++tracker_idx) { - auto & object0_state = inner_tracker_objects_.at(tracker_idx); + auto & object0_state = + inner_tracker_objects_.at(static_cast::size_type>(tracker_idx)); if (direct_assignment.find(tracker_idx) != direct_assignment.end()) { // found and merge - const auto & object1 = objects1.at(direct_assignment.at(tracker_idx)); + const auto & object1 = + objects1.at(static_cast::size_type>(direct_assignment.at(tracker_idx))); // merge object1 into object0_state object0_state.updateState(input_sensor, current_time, object1); } else { // not found @@ -328,7 +332,7 @@ bool DecorativeTrackerMergerNode::decorativeMerger( } // look for new object for (int object1_idx = 0; object1_idx < static_cast(objects1.size()); ++object1_idx) { - const auto & object1 = objects1.at(object1_idx); + const auto & object1 = objects1.at(static_cast::size_type>(object1_idx)); if (reverse_assignment.find(object1_idx) != reverse_assignment.end()) { // found } else { // not found inner_tracker_objects_.push_back(createNewTracker(input_sensor, current_time, object1)); From 1e372668b68676f9e2dc92613e5765654bb352e7 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 17:16:24 +0900 Subject: [PATCH 161/273] fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-unused-variable (#9401) Signed-off-by: kobayu858 --- .../autoware_behavior_path_lane_change_module/src/scene.cpp | 1 - 1 file changed, 1 deletion(-) 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 c6d8248be134c..1c2e6ba1c5b85 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 @@ -1143,7 +1143,6 @@ std::vector NormalLaneChange::get_lane_changing_metrics( const PathWithLaneId & prep_segment, const LaneChangePhaseMetrics & prep_metric, const double shift_length, const double dist_to_reg_element) const { - const auto & route_handler = getRouteHandler(); const auto & transient_data = common_data_ptr_->transient_data; const auto dist_lc_start_to_end_of_lanes = calculation::calc_dist_from_pose_to_terminal_end( common_data_ptr_, common_data_ptr_->lanes_ptr->target_neighbor, From 210ff63ea059cd22007c61e630d217e545e85d12 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 17:26:41 +0900 Subject: [PATCH 162/273] fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (#9510) Signed-off-by: kobayu858 --- .../image_projection_based_fusion/roi_cluster_fusion/node.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp index abececee35c25..2c0283a190023 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_cluster_fusion/node.hpp @@ -54,7 +54,7 @@ class RoiClusterFusionNode double trust_object_distance_; std::string non_trust_object_iou_mode_{"iou_x"}; bool is_far_enough(const DetectedObjectWithFeature & obj, const double distance_threshold); - bool out_of_scope(const DetectedObjectWithFeature & obj); + bool out_of_scope(const DetectedObjectWithFeature & obj) override; double cal_iou_by_mode( const sensor_msgs::msg::RegionOfInterest & roi_1, const sensor_msgs::msg::RegionOfInterest & roi_2, const std::string iou_mode); From b77f091e016585a8c1517006be944eda051d98cd Mon Sep 17 00:00:00 2001 From: "Kem (TiankuiXian)" <1041084556@qq.com> Date: Thu, 28 Nov 2024 18:28:31 +0900 Subject: [PATCH 163/273] feat(control_evaluator, tier4_control_launch): add a trigger to choice whether to output metrics to log folder (#9478) * refactor and add output_metrics. a bug existing when psim. Signed-off-by: xtk8532704 <1041084556@qq.com> * refactored launch file. Signed-off-by: xtk8532704 <1041084556@qq.com> * output description Signed-off-by: xtk8532704 <1041084556@qq.com> * add parm to launch file. Signed-off-by: xtk8532704 <1041084556@qq.com> * move output_metrics from param config to launch file. Signed-off-by: xtk8532704 <1041084556@qq.com> * move output_metrics from config to launch.xml Signed-off-by: xtk8532704 <1041084556@qq.com> * fix unit test bug. Signed-off-by: xtk8532704 <1041084556@qq.com> * fix test bug again. Signed-off-by: xtk8532704 <1041084556@qq.com> * Update evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp --------- Signed-off-by: xtk8532704 <1041084556@qq.com> Co-authored-by: Kosuke Takeuchi --- .../autoware_control_evaluator/README.md | 6 +- .../control_evaluator_node.hpp | 23 +++- .../control_evaluator/metrics/metric.hpp | 81 +++++++++++++ .../launch/control_evaluator.launch.xml | 14 +-- .../autoware_control_evaluator/package.xml | 1 + .../src/control_evaluator_node.cpp | 113 +++++++++++++----- .../test/test_control_evaluator_node.cpp | 1 + .../launch/control.launch.xml | 18 +-- 8 files changed, 198 insertions(+), 59 deletions(-) create mode 100644 evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp diff --git a/evaluator/autoware_control_evaluator/README.md b/evaluator/autoware_control_evaluator/README.md index 59c09015bd7b5..b7da418764959 100644 --- a/evaluator/autoware_control_evaluator/README.md +++ b/evaluator/autoware_control_evaluator/README.md @@ -4,14 +4,14 @@ This package provides nodes that generate metrics to evaluate the quality of control. -It publishes diagnostic information about control modules' outputs as well as the ego vehicle's current kinematics and position. +It publishes metric information about control modules' outputs as well as the ego vehicle's current kinematics and position. ## Evaluated metrics -The control evaluator uses the metrics defined in `include/autoware/control_evaluator/metrics/deviation_metrics.hpp`to calculate deviations in yaw and lateral distance from the ego's set-point. The control_evaluator can also be customized to offer metrics/evaluation about other control modules. Currently, the control_evaluator offers a simple diagnostic output based on the autonomous_emergency_braking node's output, but this functionality can be extended to evaluate other control modules' performance. +The control evaluator uses the metrics defined in `include/autoware/control_evaluator/metrics/metric.hpp`to calculate deviations in yaw and lateral distance from the ego's set-point. The control_evaluator can also be customized to offer metrics/evaluation about other control modules. Currently, the control_evaluator offers a simple metric output based on the autonomous_emergency_braking node's output, but this functionality can be extended to evaluate other control modules' performance. ## Kinematics output -The control evaluator module also constantly publishes information regarding the ego vehicle's kinematics and position. It publishes the current ego lane id with the longitudinal `s` and lateral `t` arc coordinates. It also publishes the current ego speed, acceleration and jerk in its diagnostic messages. +The control evaluator module also constantly publishes information regarding the ego vehicle's kinematics and position. It publishes the current ego lane id with the longitudinal `s` and lateral `t` arc coordinates. It also publishes the current ego speed, acceleration and jerk in its metric messages. This information can be used by other nodes to establish automated evaluation using rosbags: by crosschecking the ego position and kinematics with the evaluated control module's output, it is possible to judge if the evaluated control modules reacted in a satisfactory way at certain interesting points of the rosbag reproduction. diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp index 6e4a04964a72c..c510b2ea46779 100644 --- a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp @@ -16,6 +16,8 @@ #define AUTOWARE__CONTROL_EVALUATOR__CONTROL_EVALUATOR_NODE_HPP_ #include "autoware/control_evaluator/metrics/deviation_metrics.hpp" +#include "autoware/control_evaluator/metrics/metric.hpp" +#include "autoware/universe_utils/math/accumulator.hpp" #include #include @@ -32,10 +34,11 @@ #include #include #include +#include namespace control_diagnostics { - +using autoware::universe_utils::Accumulator; using autoware_planning_msgs::msg::Trajectory; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; @@ -53,6 +56,9 @@ class ControlEvaluatorNode : public rclcpp::Node { public: explicit ControlEvaluatorNode(const rclcpp::NodeOptions & node_options); + ~ControlEvaluatorNode() override; + + void AddMetricMsg(const Metric & metric, const double & metric_value); void AddLateralDeviationMetricMsg(const Trajectory & traj, const Point & ego_point); void AddYawDeviationMetricMsg(const Trajectory & traj, const Pose & ego_pose); void AddGoalLongitudinalDeviationMetricMsg(const Pose & ego_pose); @@ -85,9 +91,18 @@ class ControlEvaluatorNode : public rclcpp::Node // update Route Handler void getRouteData(); - // Calculator - // Metrics - std::deque stamps_; + // Parameters + bool output_metrics_; + + // Metric + const std::vector metrics_ = { + // collect all metrics + Metric::lateral_deviation, Metric::yaw_deviation, Metric::goal_longitudinal_deviation, + Metric::goal_lateral_deviation, Metric::goal_yaw_deviation, + }; + + std::array, static_cast(Metric::SIZE)> + metric_accumulators_; // 3(min, max, mean) * metric_size MetricArrayMsg metrics_msg_; autoware::route_handler::RouteHandler route_handler_; diff --git a/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp new file mode 100644 index 0000000000000..be2f3135d7f7e --- /dev/null +++ b/evaluator/autoware_control_evaluator/include/autoware/control_evaluator/metrics/metric.hpp @@ -0,0 +1,81 @@ +// Copyright 2021 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__CONTROL_EVALUATOR__METRICS__METRIC_HPP_ +#define AUTOWARE__CONTROL_EVALUATOR__METRICS__METRIC_HPP_ + +#include +#include +#include +#include + +namespace control_diagnostics +{ +/** + * @brief Enumeration of trajectory metrics + */ +enum class Metric { + lateral_deviation, + yaw_deviation, + goal_longitudinal_deviation, + goal_lateral_deviation, + goal_yaw_deviation, + SIZE, +}; + +static const std::unordered_map str_to_metric = { + {"lateral_deviation", Metric::lateral_deviation}, + {"yaw_deviation", Metric::yaw_deviation}, + {"goal_longitudinal_deviation", Metric::goal_longitudinal_deviation}, + {"goal_lateral_deviation", Metric::goal_lateral_deviation}, + {"goal_yaw_deviation", Metric::goal_yaw_deviation}, +}; + +static const std::unordered_map metric_to_str = { + {Metric::lateral_deviation, "lateral_deviation"}, + {Metric::yaw_deviation, "yaw_deviation"}, + {Metric::goal_longitudinal_deviation, "goal_longitudinal_deviation"}, + {Metric::goal_lateral_deviation, "goal_lateral_deviation"}, + {Metric::goal_yaw_deviation, "goal_yaw_deviation"}, +}; + +// Metrics descriptions +static const std::unordered_map metric_descriptions = { + {Metric::lateral_deviation, "Lateral deviation from the reference trajectory[m]"}, + {Metric::yaw_deviation, "Yaw deviation from the reference trajectory[rad]"}, + {Metric::goal_longitudinal_deviation, "Longitudinal deviation from the goal point[m]"}, + {Metric::goal_lateral_deviation, "Lateral deviation from the goal point[m]"}, + {Metric::goal_yaw_deviation, "Yaw deviation from the goal point[rad]"}}; + +namespace details +{ +static struct CheckCorrectMaps +{ + CheckCorrectMaps() + { + if ( + str_to_metric.size() != static_cast(Metric::SIZE) || + metric_to_str.size() != static_cast(Metric::SIZE) || + metric_descriptions.size() != static_cast(Metric::SIZE)) { + std::cerr << "[metrics/metrics.hpp] Maps are not defined for all metrics: "; + std::cerr << str_to_metric.size() << " " << metric_to_str.size() << " " + << metric_descriptions.size() << std::endl; + } + } +} check; + +} // namespace details +} // namespace control_diagnostics + +#endif // AUTOWARE__CONTROL_EVALUATOR__METRICS__METRIC_HPP_ diff --git a/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml b/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml index e9fee7ffadbf2..4cf795afb5a7d 100644 --- a/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml +++ b/evaluator/autoware_control_evaluator/launch/control_evaluator.launch.xml @@ -1,20 +1,20 @@ - + - - + + + - - + - - + + diff --git a/evaluator/autoware_control_evaluator/package.xml b/evaluator/autoware_control_evaluator/package.xml index 8ab2c73cb619a..1c724fc7bd0ec 100644 --- a/evaluator/autoware_control_evaluator/package.xml +++ b/evaluator/autoware_control_evaluator/package.xml @@ -22,6 +22,7 @@ autoware_test_utils autoware_universe_utils nav_msgs + nlohmann-json-dev pluginlib rclcpp rclcpp_components diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index c24dfee571852..2a2c07b2db319 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -16,7 +16,11 @@ #include #include +#include +#include +#include +#include #include #include #include @@ -33,12 +37,63 @@ ControlEvaluatorNode::ControlEvaluatorNode(const rclcpp::NodeOptions & node_opti this->create_publisher("~/debug/processing_time_ms", 1); metrics_pub_ = create_publisher("~/metrics", 1); + // Parameters + output_metrics_ = declare_parameter("output_metrics"); + // Timer callback to publish evaluator diagnostics using namespace std::literals::chrono_literals; timer_ = rclcpp::create_timer(this, get_clock(), 100ms, std::bind(&ControlEvaluatorNode::onTimer, this)); } +ControlEvaluatorNode::~ControlEvaluatorNode() +{ + if (!output_metrics_) { + return; + } + + // generate json data + using json = nlohmann::json; + json j; + for (Metric metric : metrics_) { + const std::string base_name = metric_to_str.at(metric) + "/"; + j[base_name + "min"] = metric_accumulators_[static_cast(metric)].min(); + j[base_name + "max"] = metric_accumulators_[static_cast(metric)].max(); + j[base_name + "mean"] = metric_accumulators_[static_cast(metric)].mean(); + j[base_name + "count"] = metric_accumulators_[static_cast(metric)].count(); + j[base_name + "description"] = metric_descriptions.at(metric); + } + + // get output folder + const std::string output_folder_str = + rclcpp::get_logging_directory().string() + "/autoware_metrics"; + if (!std::filesystem::exists(output_folder_str)) { + if (!std::filesystem::create_directories(output_folder_str)) { + RCLCPP_ERROR( + this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); + return; + } + } + + // get time stamp + std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::tm * local_time = std::localtime(&now_time_t); + std::ostringstream oss; + oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); + std::string cur_time_str = oss.str(); + + // Write metrics .json to file + const std::string output_file_str = + output_folder_str + "/autoware_control_evaluator-" + cur_time_str + ".json"; + std::ofstream f(output_file_str); + if (f.is_open()) { + f << j.dump(4); + f.close(); + } else { + RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + } +} + void ControlEvaluatorNode::getRouteData() { // route @@ -62,6 +117,18 @@ void ControlEvaluatorNode::getRouteData() } } +void ControlEvaluatorNode::AddMetricMsg(const Metric & metric, const double & metric_value) +{ + MetricMsg metric_msg; + metric_msg.name = metric_to_str.at(metric); + metric_msg.value = std::to_string(metric_value); + metrics_msg_.metric_array.push_back(metric_msg); + + if (output_metrics_) { + metric_accumulators_[static_cast(metric)].add(metric_value); + } +} + void ControlEvaluatorNode::AddLaneletMetricMsg(const Pose & ego_pose) { const auto current_lanelets = [&]() { @@ -97,7 +164,6 @@ void ControlEvaluatorNode::AddLaneletMetricMsg(const Pose & ego_pose) metric_msg.value = std::to_string(arc_coordinates.distance); metrics_msg_.metric_array.push_back(metric_msg); } - return; } void ControlEvaluatorNode::AddKinematicStateMetricMsg( @@ -141,59 +207,44 @@ void ControlEvaluatorNode::AddKinematicStateMetricMsg( void ControlEvaluatorNode::AddLateralDeviationMetricMsg( const Trajectory & traj, const Point & ego_point) { - const double lateral_deviation = metrics::calcLateralDeviation(traj, ego_point); + const Metric metric = Metric::lateral_deviation; + const double metric_value = metrics::calcLateralDeviation(traj, ego_point); - MetricMsg metric_msg; - metric_msg.name = "lateral_deviation"; - metric_msg.value = std::to_string(lateral_deviation); - metrics_msg_.metric_array.push_back(metric_msg); - return; + AddMetricMsg(metric, metric_value); } void ControlEvaluatorNode::AddYawDeviationMetricMsg(const Trajectory & traj, const Pose & ego_pose) { - const double yaw_deviation = metrics::calcYawDeviation(traj, ego_pose); + const Metric metric = Metric::yaw_deviation; + const double metric_value = metrics::calcYawDeviation(traj, ego_pose); - MetricMsg metric_msg; - metric_msg.name = "yaw_deviation"; - metric_msg.value = std::to_string(yaw_deviation); - metrics_msg_.metric_array.push_back(metric_msg); - return; + AddMetricMsg(metric, metric_value); } void ControlEvaluatorNode::AddGoalLongitudinalDeviationMetricMsg(const Pose & ego_pose) { - const double longitudinal_deviation = + const Metric metric = Metric::goal_longitudinal_deviation; + const double metric_value = metrics::calcLongitudinalDeviation(route_handler_.getGoalPose(), ego_pose.position); - MetricMsg metric_msg; - metric_msg.name = "goal_longitudinal_deviation"; - metric_msg.value = std::to_string(longitudinal_deviation); - metrics_msg_.metric_array.push_back(metric_msg); - return; + AddMetricMsg(metric, metric_value); } void ControlEvaluatorNode::AddGoalLateralDeviationMetricMsg(const Pose & ego_pose) { - const double lateral_deviation = + const Metric metric = Metric::lateral_deviation; + const double metric_value = metrics::calcLateralDeviation(route_handler_.getGoalPose(), ego_pose.position); - MetricMsg metric_msg; - metric_msg.name = "goal_lateral_deviation"; - metric_msg.value = std::to_string(lateral_deviation); - metrics_msg_.metric_array.push_back(metric_msg); - return; + AddMetricMsg(metric, metric_value); } void ControlEvaluatorNode::AddGoalYawDeviationMetricMsg(const Pose & ego_pose) { - const double yaw_deviation = metrics::calcYawDeviation(route_handler_.getGoalPose(), ego_pose); + const Metric metric = Metric::goal_yaw_deviation; + const double metric_value = metrics::calcYawDeviation(route_handler_.getGoalPose(), ego_pose); - MetricMsg metric_msg; - metric_msg.name = "goal_yaw_deviation"; - metric_msg.value = std::to_string(yaw_deviation); - metrics_msg_.metric_array.push_back(metric_msg); - return; + AddMetricMsg(metric, metric_value); } void ControlEvaluatorNode::onTimer() diff --git a/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp index 0a2f777e49b61..728cef03901a8 100644 --- a/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp @@ -52,6 +52,7 @@ class EvalTest : public ::testing::Test rclcpp::NodeOptions options; const auto share_dir = ament_index_cpp::get_package_share_directory("autoware_control_evaluator"); + options.arguments({"--ros-args", "-p", "output_metrics:=false"}); dummy_node = std::make_shared("control_evaluator_test_node"); eval_node = std::make_shared(options); diff --git a/launch/tier4_control_launch/launch/control.launch.xml b/launch/tier4_control_launch/launch/control.launch.xml index 899db1448dbf8..387b82526f624 100644 --- a/launch/tier4_control_launch/launch/control.launch.xml +++ b/launch/tier4_control_launch/launch/control.launch.xml @@ -269,21 +269,11 @@ + - - - - - - - - - - - - - - + + + From c1bbd68dd77777810888e3d50666c7438c6c40ba Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Thu, 28 Nov 2024 18:33:17 +0900 Subject: [PATCH 164/273] feat(clang-tidy): add .clang-tidy-ignore (#9498) * feat(clang-tidy): add .clang-tidy-ignore Signed-off-by: Y.Hisaki * clang-tidy-ignore path as argument Signed-off-by: Y.Hisaki * commit for test action Signed-off-by: Y.Hisaki * commit for test action Signed-off-by: Y.Hisaki * style(pre-commit): autofix * use v1 Signed-off-by: Y.Hisaki * change time_utils Signed-off-by: Y.Hisaki * revert commit for test Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .clang-tidy-ignore | 2 ++ .github/workflows/build-and-test-differential.yaml | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) create mode 100644 .clang-tidy-ignore diff --git a/.clang-tidy-ignore b/.clang-tidy-ignore new file mode 100644 index 0000000000000..a7110b007db10 --- /dev/null +++ b/.clang-tidy-ignore @@ -0,0 +1,2 @@ +*/examples/* +perception/* diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 871fc67499f48..540ab64b4f279 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -109,8 +109,8 @@ jobs: with: rosdistro: humble target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} - target-files: ${{ steps.get-changed-files.outputs.changed-files }} clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy-ci + clang-tidy-ignore-path: .clang-tidy-ignore build-depends-repos: build_depends.repos cache-key-element: cuda From d240d2e8fd9e2a251584ca99fbea7c59aa0a1c76 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 20:36:50 +0900 Subject: [PATCH 165/273] fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (#9516) fix: clang-diagnostic-inconsistent-missing-override Signed-off-by: kobayu858 --- .../image_projection_based_fusion/pointpainting_fusion/node.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp index aa3e3fe096306..8c0e2ed78fc6c 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp @@ -76,7 +76,7 @@ class PointPaintingFusionNode std::unique_ptr detector_ptr_{nullptr}; - bool out_of_scope(const DetectedObjects & obj); + bool out_of_scope(const DetectedObjects & obj) override; }; } // namespace autoware::image_projection_based_fusion #endif // AUTOWARE__IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__NODE_HPP_ From fdc7a558baa9079119ef4b809ddfb71b14cf6381 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Thu, 28 Nov 2024 20:37:17 +0900 Subject: [PATCH 166/273] fix(autoware_tensorrt_yolox): fix clang-diagnostic-inconsistent-missing-override (#9512) fix: clang-diagnostic-inconsistent-missing-override Signed-off-by: kobayu858 --- .../include/autoware/tensorrt_yolox/calibrator.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/calibrator.hpp b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/calibrator.hpp index 3a2bac315a3d0..46305b12c0de6 100644 --- a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/calibrator.hpp +++ b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/calibrator.hpp @@ -248,19 +248,19 @@ class Int8LegacyCalibrator : public nvinfer1::IInt8LegacyCalibrator output.write(reinterpret_cast(cache), length); } - double getQuantile() const noexcept + double getQuantile() const noexcept override { printf("Quantile %f\n", quantile_); return quantile_; } - double getRegressionCutoff(void) const noexcept + double getRegressionCutoff(void) const noexcept override { printf("Cutoff %f\n", cutoff_); return cutoff_; } - const void * readHistogramCache(std::size_t & length) noexcept + const void * readHistogramCache(std::size_t & length) noexcept override { hist_cache_.clear(); std::ifstream input(histogram_cache_file_, std::ios::binary); @@ -279,7 +279,7 @@ class Int8LegacyCalibrator : public nvinfer1::IInt8LegacyCalibrator } return length ? &hist_cache_[0] : nullptr; } - void writeHistogramCache(void const * ptr, std::size_t length) noexcept + void writeHistogramCache(void const * ptr, std::size_t length) noexcept override { std::ofstream output(histogram_cache_file_, std::ios::binary); output.write(reinterpret_cast(ptr), length); From 45a3c487773730a31192bc1132e74f4fa651578e Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 29 Nov 2024 00:30:37 +0900 Subject: [PATCH 167/273] refactor(autoware_behavior_velocity_stop_line_module): refactor and test (#9424) * refactor(autoware_behavior_velocity_stop_line_module): refactor and test Signed-off-by: Y.Hisaki * modify Signed-off-by: Y.Hisaki * small changes Signed-off-by: Y.Hisaki * update Signed-off-by: Y.Hisaki * fix test error Signed-off-by: Y.Hisaki * update Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../CMakeLists.txt | 11 + .../config/stop_line.param.yaml | 4 - .../package.xml | 1 + .../src/debug.cpp | 77 ------ .../src/manager.cpp | 13 +- .../src/manager.hpp | 1 - .../src/scene.cpp | 226 ++++++++++-------- .../src/scene.hpp | 103 +++++--- .../test/test_scene.cpp | 143 +++++++++++ 9 files changed, 351 insertions(+), 228 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CMakeLists.txt index 402eb5e20aa24..f4528f0d13cf4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CMakeLists.txt @@ -11,4 +11,15 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/scene.cpp ) +if(BUILD_TESTING) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} + test/test_scene.cpp + ) + target_link_libraries(test_${PROJECT_NAME} + gtest_main + ${PROJECT_NAME} + ) + target_include_directories(test_${PROJECT_NAME} PRIVATE src) +endif() + ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/config/stop_line.param.yaml b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/config/stop_line.param.yaml index 7b1d82a46f652..f5e00fa7087ae 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/config/stop_line.param.yaml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/config/stop_line.param.yaml @@ -3,8 +3,4 @@ stop_line: stop_margin: 0.0 stop_duration_sec: 1.0 - use_initialization_stop_line_state: true hold_stop_margin_distance: 2.0 - - debug: - show_stop_line_collision_check: false # [-] whether to show stopline collision diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml index e24f167eb2058..c5e3690dd620d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml @@ -33,6 +33,7 @@ tf2_geometry_msgs visualization_msgs + ament_cmake_ros ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp index 573a260138679..fa94bfbaa361b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/debug.cpp @@ -12,89 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware/behavior_velocity_planner_common/utilization/util.hpp" #include "autoware/motion_utils/marker/virtual_wall_marker_creator.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "autoware/universe_utils/ros/marker_helper.hpp" #include "scene.hpp" -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - namespace autoware::behavior_velocity_planner { -using autoware::universe_utils::appendMarkerArray; -using autoware::universe_utils::createMarkerColor; -using autoware::universe_utils::createMarkerScale; - -namespace -{ -using DebugData = StopLineModule::DebugData; - -visualization_msgs::msg::MarkerArray createStopLineCollisionCheck( - const DebugData & debug_data, const int64_t module_id) -{ - visualization_msgs::msg::MarkerArray msg; - - // Search Segments - { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.ns = "search_segments"; - marker.id = module_id; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::SPHERE_LIST; - marker.action = visualization_msgs::msg::Marker::ADD; - for (const auto & e : debug_data.search_segments) { - marker.points.push_back( - geometry_msgs::build().x(e.at(0).x()).y(e.at(0).y()).z(0.0)); - marker.points.push_back( - geometry_msgs::build().x(e.at(1).x()).y(e.at(1).y()).z(0.0)); - } - marker.scale = createMarkerScale(0.1, 0.1, 0.1); - marker.color = createMarkerColor(0.0, 0.0, 1.0, 0.999); - msg.markers.push_back(marker); - } - - // Search stopline - { - visualization_msgs::msg::Marker marker; - marker.header.frame_id = "map"; - marker.ns = "search_stopline"; - marker.id = module_id; - marker.lifetime = rclcpp::Duration::from_seconds(0.5); - marker.type = visualization_msgs::msg::Marker::LINE_STRIP; - marker.action = visualization_msgs::msg::Marker::ADD; - const auto p0 = debug_data.search_stopline.at(0); - marker.points.push_back( - geometry_msgs::build().x(p0.x()).y(p0.y()).z(0.0)); - const auto p1 = debug_data.search_stopline.at(1); - marker.points.push_back( - geometry_msgs::build().x(p1.x()).y(p1.y()).z(0.0)); - - marker.scale = createMarkerScale(0.1, 0.1, 0.1); - marker.color = createMarkerColor(1.0, 0.0, 0.0, 0.999); - msg.markers.push_back(marker); - } - - return msg; -} - -} // namespace - -visualization_msgs::msg::MarkerArray StopLineModule::createDebugMarkerArray() -{ - visualization_msgs::msg::MarkerArray debug_marker_array; - if (planner_param_.show_stop_line_collision_check) { - appendMarkerArray( - createStopLineCollisionCheck(debug_data_, module_id_), &debug_marker_array, - this->clock_->now()); - } - return debug_marker_array; -} autoware::motion_utils::VirtualWalls StopLineModule::createVirtualWalls() { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp index ffdcea16b45b5..b305a1d2aa404 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.cpp @@ -15,7 +15,8 @@ #include "manager.hpp" #include "autoware/universe_utils/ros/parameter.hpp" -#include "autoware_lanelet2_extension/utility/query.hpp" + +#include #include #include @@ -28,7 +29,7 @@ using autoware::universe_utils::getOrDeclareParameter; using lanelet::TrafficSign; StopLineModuleManager::StopLineModuleManager(rclcpp::Node & node) -: SceneModuleManagerInterface(node, getModuleName()) +: SceneModuleManagerInterface(node, getModuleName()), planner_param_() { const std::string ns(StopLineModuleManager::getModuleName()); auto & p = planner_param_; @@ -36,11 +37,6 @@ StopLineModuleManager::StopLineModuleManager(rclcpp::Node & node) p.hold_stop_margin_distance = getOrDeclareParameter(node, ns + ".hold_stop_margin_distance"); p.stop_duration_sec = getOrDeclareParameter(node, ns + ".stop_duration_sec"); - p.use_initialization_stop_line_state = - getOrDeclareParameter(node, ns + ".use_initialization_stop_line_state"); - // debug - p.show_stop_line_collision_check = - getOrDeclareParameter(node, ns + ".debug.show_stop_line_collision_check"); } std::vector StopLineModuleManager::getStopLinesWithLaneIdOnPath( @@ -82,10 +78,9 @@ void StopLineModuleManager::launchNewModules(const tier4_planning_msgs::msg::Pat for (const auto & stop_line_with_lane_id : getStopLinesWithLaneIdOnPath(path, planner_data_->route_handler_->getLaneletMapPtr())) { const auto module_id = stop_line_with_lane_id.first.id(); - const auto lane_id = stop_line_with_lane_id.second; if (!isModuleRegistered(module_id)) { registerModule(std::make_shared( - module_id, lane_id, stop_line_with_lane_id.first, planner_param_, + module_id, stop_line_with_lane_id.first, planner_param_, logger_.get_child("stop_line_module"), clock_)); } } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp index b83a4f94e9a1f..bef8a5eef4ac0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/manager.hpp @@ -15,7 +15,6 @@ #ifndef MANAGER_HPP_ #define MANAGER_HPP_ -#include "autoware/behavior_velocity_planner_common/plugin_interface.hpp" #include "autoware/behavior_velocity_planner_common/plugin_wrapper.hpp" #include "autoware/behavior_velocity_planner_common/scene_module_interface.hpp" #include "scene.hpp" diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index 6a4b85cd6926c..b83a274f99513 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -15,22 +15,32 @@ #include "scene.hpp" #include "autoware/behavior_velocity_planner_common/utilization/util.hpp" -#include "autoware/trajectory/path_point_with_lane_id.hpp" -#include +#include + +#include + +#include namespace autoware::behavior_velocity_planner { +geometry_msgs::msg::Point getCenterOfStopLine(const lanelet::ConstLineString3d & stop_line) +{ + geometry_msgs::msg::Point center_point; + center_point.x = (stop_line[0].x() + stop_line[1].x()) / 2.0; + center_point.y = (stop_line[0].y() + stop_line[1].y()) / 2.0; + center_point.z = (stop_line[0].z() + stop_line[1].z()) / 2.0; + return center_point; +} + StopLineModule::StopLineModule( - const int64_t module_id, const size_t lane_id, lanelet::ConstLineString3d stop_line, - const PlannerParam & planner_param, const rclcpp::Logger & logger, - const rclcpp::Clock::SharedPtr clock) + const int64_t module_id, lanelet::ConstLineString3d stop_line, const PlannerParam & planner_param, + const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), - lane_id_(lane_id), stop_line_(std::move(stop_line)), - state_(State::APPROACH), planner_param_(planner_param), + state_(State::APPROACH), debug_data_() { velocity_factor_.init(PlanningBehavior::STOP_SIGN); @@ -46,132 +56,144 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop return true; } - debug_data_ = DebugData(); - const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; - debug_data_.base_link2front = base_link2front; - first_stop_path_point_distance_ = trajectory->length(); - *stop_reason = planning_utils::initializeStopReason(StopReason::STOP_LINE); - - const LineString2d stop_line = planning_utils::extendLine( - stop_line_[0], stop_line_[1], planner_data_->stop_line_extend_length); - - // Calculate intersection with stop line - const auto trajectory_stop_line_intersection = - trajectory->crossed(stop_line.front(), stop_line.back()); + auto [ego_s, stop_point] = + getEgoAndStopPoint(*trajectory, planner_data_->current_odometry->pose, state_); - // If no collision found, do nothing - if (!trajectory_stop_line_intersection) { - RCLCPP_DEBUG_THROTTLE(logger_, *clock_, 5000 /* ms */, "is no collision"); + if (!stop_point) { return true; } - const double stop_point_s = - *trajectory_stop_line_intersection - - (base_link2front + planner_param_.stop_margin); // consider vehicle length and stop margin + trajectory->longitudinal_velocity_mps.range(*stop_point, trajectory->length()).set(0.0); - if (stop_point_s < 0.0) { - return true; - } + path->points = trajectory->restore(); - const auto stop_pose = trajectory->compute(stop_point_s); + updateVelocityFactor(&velocity_factor_, state_, *stop_point - ego_s); - /** - * @brief : calculate signed arc length consider stop margin from stop line - * - * |----------------------------| - * s---ego----------x--|--------g - */ - const double ego_on_trajectory_s = - trajectory->closest(planner_data_->current_odometry->pose.position); - const double signed_arc_dist_to_stop_point = stop_point_s - ego_on_trajectory_s; + updateStateAndStoppedTime( + &state_, &stopped_time_, clock_->now(), *stop_point - ego_s, planner_data_->isVehicleStopped()); - switch (state_) { - case State::APPROACH: { - // Insert stop pose - trajectory->longitudinal_velocity_mps.range(stop_point_s, trajectory->length()).set(0.0); - - // Update first stop path point distance - first_stop_path_point_distance_ = stop_point_s; - debug_data_.stop_pose = stop_pose.point.pose; - - // Get stop point and stop factor - { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = stop_pose.point.pose; - stop_factor.stop_factor_points.push_back(getCenterOfStopLine(stop_line_)); - planning_utils::appendStopReason(stop_factor, stop_reason); - velocity_factor_.set(signed_arc_dist_to_stop_point, VelocityFactor::APPROACHING); - } + geometry_msgs::msg::Pose stop_pose = trajectory->compute(*stop_point).point.pose; - // Move to stopped state if stopped - if ( - signed_arc_dist_to_stop_point < planner_param_.hold_stop_margin_distance && - planner_data_->isVehicleStopped()) { - RCLCPP_INFO(logger_, "APPROACH -> STOPPED"); + updateStopReason(stop_reason, stop_pose); - state_ = State::STOPPED; - stopped_time_ = std::make_shared(clock_->now()); + updateDebugData(&debug_data_, stop_pose, state_); - if (signed_arc_dist_to_stop_point < -planner_param_.hold_stop_margin_distance) { - RCLCPP_ERROR( - logger_, "Failed to stop near stop line but ego stopped. Change state to STOPPED"); - } - } + return true; +} - break; - } +std::pair> StopLineModule::getEgoAndStopPoint( + const Trajectory & trajectory, const geometry_msgs::msg::Pose & ego_pose, + const State & state) const +{ + const double ego_s = trajectory.closest(ego_pose.position); + std::optional stop_point_s; - case State::STOPPED: { - // Insert stop pose - trajectory->longitudinal_velocity_mps.range(ego_on_trajectory_s, trajectory->length()) - .set(0.0); - const auto ego_pos_on_path = trajectory->compute(ego_on_trajectory_s).point.pose; - debug_data_.stop_pose = ego_pos_on_path; - - // Get stop point and stop factor - { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = ego_pos_on_path; - stop_factor.stop_factor_points.push_back(getCenterOfStopLine(stop_line_)); - planning_utils::appendStopReason(stop_factor, stop_reason); - velocity_factor_.set(signed_arc_dist_to_stop_point, VelocityFactor::STOPPED); + switch (state) { + case State::APPROACH: { + const double base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + const LineString2d stop_line = planning_utils::extendLine( + stop_line_[0], stop_line_[1], planner_data_->stop_line_extend_length); + + // Calculate intersection with stop line + const auto trajectory_stop_line_intersection = + trajectory.crossed(stop_line.front(), stop_line.back()); + + // If no collision found, do nothing + if (!trajectory_stop_line_intersection) { + stop_point_s = std::nullopt; + break; } - const double elapsed_time = (clock_->now() - *stopped_time_).seconds(); + stop_point_s = + *trajectory_stop_line_intersection - + (base_link2front + planner_param_.stop_margin); // consider vehicle length and stop margin - if (planner_param_.stop_duration_sec < elapsed_time) { - RCLCPP_INFO(logger_, "STOPPED -> START"); - state_ = State::START; + if (*stop_point_s < 0.0) { + stop_point_s = std::nullopt; } + break; + } + case State::STOPPED: { + stop_point_s = ego_s; break; } case State::START: { - // Initialize if vehicle is far from stop_line - if (planner_param_.use_initialization_stop_line_state) { - if (signed_arc_dist_to_stop_point > planner_param_.hold_stop_margin_distance) { - RCLCPP_INFO(logger_, "START -> APPROACH"); - state_ = State::APPROACH; + stop_point_s = std::nullopt; + break; + } + } + return {ego_s, stop_point_s}; +} + +void StopLineModule::updateStateAndStoppedTime( + State * state, std::optional * stopped_time, const rclcpp::Time & now, + const double & distance_to_stop_point, const bool & is_vehicle_stopped) const +{ + switch (*state) { + case State::APPROACH: { + if (distance_to_stop_point < planner_param_.hold_stop_margin_distance && is_vehicle_stopped) { + *state = State::STOPPED; + *stopped_time = now; + RCLCPP_INFO(logger_, "APPROACH -> STOPPED"); + + if (distance_to_stop_point < 0.0) { + RCLCPP_WARN(logger_, "Vehicle cannot stop before stop line"); } } - + break; + } + case State::STOPPED: { + double stop_duration = (now - **stopped_time).seconds(); + if (stop_duration > planner_param_.stop_duration_sec) { + *state = State::START; + stopped_time->reset(); + RCLCPP_INFO(logger_, "STOPPED -> START"); + } + break; + } + case State::START: { break; } } +} - path->points = trajectory->restore(); +void StopLineModule::updateVelocityFactor( + autoware::motion_utils::VelocityFactorInterface * velocity_factor, const State & state, + const double & distance_to_stop_point) +{ + switch (state) { + case State::APPROACH: { + velocity_factor->set(distance_to_stop_point, VelocityFactor::APPROACHING); + break; + } + case State::STOPPED: { + velocity_factor->set(distance_to_stop_point, VelocityFactor::STOPPED); + break; + } + case State::START: + break; + } +} - return true; +void StopLineModule::updateStopReason( + StopReason * stop_reason, const geometry_msgs::msg::Pose & stop_pose) const +{ + tier4_planning_msgs::msg::StopFactor stop_factor; + stop_factor.stop_pose = stop_pose; + stop_factor.stop_factor_points.push_back(getCenterOfStopLine(stop_line_)); + planning_utils::appendStopReason(stop_factor, stop_reason); } -geometry_msgs::msg::Point StopLineModule::getCenterOfStopLine( - const lanelet::ConstLineString3d & stop_line) +void StopLineModule::updateDebugData( + DebugData * debug_data, const geometry_msgs::msg::Pose & stop_pose, const State & state) const { - geometry_msgs::msg::Point center_point; - center_point.x = (stop_line[0].x() + stop_line[1].x()) / 2.0; - center_point.y = (stop_line[0].y() + stop_line[1].y()) / 2.0; - center_point.z = (stop_line[0].z() + stop_line[1].z()) / 2.0; - return center_point; + debug_data->base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; + debug_data->stop_pose = stop_pose; + if (state == State::START) { + debug_data->stop_pose = std::nullopt; + } } + } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp index cb48aabe57c1a..cb5bf339f8846 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp @@ -14,75 +14,108 @@ #ifndef SCENE_HPP_ #define SCENE_HPP_ +#define EIGEN_MPL2_ONLY #include "autoware/behavior_velocity_planner_common/scene_module_interface.hpp" -#include "autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp" #include "autoware/behavior_velocity_planner_common/utilization/util.hpp" +#include "autoware/motion_utils/factor/velocity_factor_interface.hpp" +#include "autoware/trajectory/path_point_with_lane_id.hpp" -#include -#include -#include - -#define EIGEN_MPL2_ONLY #include #include #include +#include + +#include #include +#include +#include + namespace autoware::behavior_velocity_planner { class StopLineModule : public SceneModuleInterface { - using StopLineWithLaneId = std::pair; - public: + using StopLineWithLaneId = std::pair; + using Trajectory = + autoware::trajectory::Trajectory; enum class State { APPROACH, STOPPED, START }; struct DebugData { - double base_link2front; - boost::optional stop_pose; - std::vector search_segments; - LineString2d search_stopline; + double base_link2front; ///< Distance from the base link to the vehicle front. + std::optional stop_pose; ///< Pose of the stop position. }; struct PlannerParam { - double stop_margin; - double stop_duration_sec; - double hold_stop_margin_distance; - bool use_initialization_stop_line_state; - bool show_stop_line_collision_check; + double stop_margin; ///< Margin to the stop line. + double stop_duration_sec; ///< Required stop duration at the stop line. + double + hold_stop_margin_distance; ///< Distance threshold for transitioning to the STOPPED state }; + /** + * @brief Constructor for StopLineModule. + * @param module_id Unique ID for the module. + * @param stop_line Stop line data. + * @param planner_param Planning parameters. + * @param logger Logger for output messages. + * @param clock Shared clock instance. + */ StopLineModule( - const int64_t module_id, const size_t lane_id, lanelet::ConstLineString3d stop_line, + const int64_t module_id, lanelet::ConstLineString3d stop_line, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; - visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; + /** + * @brief Calculate ego position and stop point. + * @param trajectory Current trajectory. + * @param ego_pose Current pose of the vehicle. + * @param state Current state of the stop line module. + * @return Pair of ego position and optional stop point. + */ + std::pair> getEgoAndStopPoint( + const Trajectory & trajectory, const geometry_msgs::msg::Pose & ego_pose, + const State & state) const; + + /** + * @brief Update the state and stopped time of the module. + * @param state Pointer to the current state. + * @param stopped_time Pointer to the stopped time. + * @param now Current time. + * @param distance_to_stop_point Distance to the stop point. + * @param is_vehicle_stopped Flag indicating if the vehicle is stopped. + */ + void updateStateAndStoppedTime( + State * state, std::optional * stopped_time, const rclcpp::Time & now, + const double & distance_to_stop_point, const bool & is_vehicle_stopped) const; + + static void updateVelocityFactor( + autoware::motion_utils::VelocityFactorInterface * velocity_factor, const State & state, + const double & distance_to_stop_point); + + void updateStopReason(StopReason * stop_reason, const geometry_msgs::msg::Pose & stop_pose) const; + + void updateDebugData( + DebugData * debug_data, const geometry_msgs::msg::Pose & stop_pose, const State & state) const; + + visualization_msgs::msg::MarkerArray createDebugMarkerArray() override + { + return visualization_msgs::msg::MarkerArray{}; + } autoware::motion_utils::VirtualWalls createVirtualWalls() override; private: - std::shared_ptr stopped_time_; - - geometry_msgs::msg::Point getCenterOfStopLine(const lanelet::ConstLineString3d & stop_line); - - int64_t lane_id_; - - lanelet::ConstLineString3d stop_line_; - - // State machine - State state_; - - // Parameter - PlannerParam planner_param_; - - // Debug - DebugData debug_data_; + const lanelet::ConstLineString3d stop_line_; ///< Stop line geometry. + const PlannerParam planner_param_; ///< Parameters for the planner. + State state_; ///< Current state of the module. + std::optional stopped_time_; ///< Time when the vehicle stopped. + DebugData debug_data_; ///< Debug information. }; } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp new file mode 100644 index 0000000000000..1eafb71eb403c --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/test/test_scene.cpp @@ -0,0 +1,143 @@ +// 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 "../src/scene.hpp" + +#include +#include +#include + +#include + +#include + +#include +#include +#include + +using autoware::behavior_velocity_planner::StopLineModule; + +tier4_planning_msgs::msg::PathPointWithLaneId path_point(double x, double y) +{ + tier4_planning_msgs::msg::PathPointWithLaneId p; + p.point.pose.position.x = x; + p.point.pose.position.y = y; + return p; +} + +class StopLineModuleTest : public ::testing::Test +{ +protected: + // Set up the test case + void SetUp() override + { + rclcpp::init(0, nullptr); + rclcpp::NodeOptions options; + options.arguments( + {"--ros-args", "--params-file", + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_planner_common") + + "/config/behavior_velocity_planner_common.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_test_utils") + + "/config/test_vehicle_info.param.yaml"}); + node_ = std::make_shared("test_node", options); + + // Initialize parameters, logger, and clock + planner_param_.stop_margin = 0.5; + planner_param_.stop_duration_sec = 2.0; + planner_param_.hold_stop_margin_distance = 0.5; + + planner_data_ = std::make_shared(*node_); + planner_data_->stop_line_extend_length = 5.0; + planner_data_->vehicle_info_.max_longitudinal_offset_m = 1.0; + + stop_line_ = lanelet::ConstLineString3d( + lanelet::utils::getId(), {lanelet::Point3d(lanelet::utils::getId(), 7.0, -1.0, 0.0), + lanelet::Point3d(lanelet::utils::getId(), 7.0, 1.0, 0.0)}); + + trajectory_ = *StopLineModule::Trajectory::Builder{}.build( + {path_point(0.0, 0.0), path_point(1.0, 0.0), path_point(2.0, 0.0), path_point(3.0, 0.0), + path_point(4.0, 0.0), path_point(5.0, 0.0), path_point(6.0, 0.0), path_point(7.0, 0.0), + path_point(8.0, 0.0), path_point(9.0, 0.0), path_point(10.0, 0.0)}); + + clock_ = std::make_shared(); + + module_ = std::make_shared( + 1, stop_line_, planner_param_, rclcpp::get_logger("test_logger"), clock_); + + module_->setPlannerData(planner_data_); + } + + void TearDown() override { rclcpp::shutdown(); } + + StopLineModule::Trajectory trajectory_; + StopLineModule::PlannerParam planner_param_{}; + lanelet::ConstLineString3d stop_line_; + rclcpp::Clock::SharedPtr clock_; + std::shared_ptr module_; + std::shared_ptr planner_data_; + + rclcpp::Node::SharedPtr node_; +}; + +TEST_F(StopLineModuleTest, TestGetEgoAndStopPoint) +{ + // Prepare trajectory and other parameters + geometry_msgs::msg::Pose ego_pose; + ego_pose.position.x = 5.0; + ego_pose.position.y = 1.0; + + // Execute the function + auto [ego_s, stop_point_s] = + module_->getEgoAndStopPoint(trajectory_, ego_pose, StopLineModule::State::APPROACH); + + // Verify results + EXPECT_DOUBLE_EQ(ego_s, 5.0); + EXPECT_DOUBLE_EQ(stop_point_s.value(), 7.0 - 0.5 - 1.0); + + std::tie(ego_s, stop_point_s) = + module_->getEgoAndStopPoint(trajectory_, ego_pose, StopLineModule::State::STOPPED); + + EXPECT_DOUBLE_EQ(ego_s, 5.0); + EXPECT_DOUBLE_EQ(stop_point_s.value(), 5.0); +} + +TEST_F(StopLineModuleTest, TestUpdateStateAndStoppedTime) +{ + StopLineModule::State state = StopLineModule::State::APPROACH; + std::optional stopped_time; + double distance_to_stop_point = 0.1; + bool is_vehicle_stopped = true; + + // Simulate clock progression + auto test_start_time = clock_->now(); + stopped_time = test_start_time; + + // Execute the function + module_->updateStateAndStoppedTime( + &state, &stopped_time, test_start_time, distance_to_stop_point, is_vehicle_stopped); + + // Verify state transition to STOPPED + EXPECT_EQ(state, StopLineModule::State::STOPPED); + EXPECT_TRUE(stopped_time.has_value()); + + // Simulate time elapsed to exceed stop duration + auto now = test_start_time + rclcpp::Duration::from_seconds(3.0); + module_->updateStateAndStoppedTime( + &state, &stopped_time, now, distance_to_stop_point, is_vehicle_stopped); + + // Verify state transition to START + EXPECT_EQ(state, StopLineModule::State::START); + EXPECT_FALSE(stopped_time.has_value()); +} From be4c9e01740910e9251f255a9a913c96fa2c3b9f Mon Sep 17 00:00:00 2001 From: "Kem (TiankuiXian)" <1041084556@qq.com> Date: Fri, 29 Nov 2024 13:14:12 +0900 Subject: [PATCH 168/273] feat(planning_evaluator): add a trigger to choice whether to output metrics to log folder (#9476) * tmp save Signed-off-by: xtk8532704 <1041084556@qq.com> * planning_evaluator build ok, test it. Signed-off-by: xtk8532704 <1041084556@qq.com> * add descriptions to output. Signed-off-by: xtk8532704 <1041084556@qq.com> * pre-commit. Signed-off-by: xtk8532704 <1041084556@qq.com> * add parm to launch file. Signed-off-by: xtk8532704 <1041084556@qq.com> * move output_metrics from config to launch file. Signed-off-by: xtk8532704 <1041084556@qq.com> * fix unit test bug. Signed-off-by: xtk8532704 <1041084556@qq.com> --------- Signed-off-by: xtk8532704 <1041084556@qq.com> --- .../autoware_planning_evaluator/README.md | 4 +- .../config/planning_evaluator.param.yaml | 1 - .../motion_evaluator_node.hpp | 2 +- .../planning_evaluator_node.hpp | 14 +-- .../launch/motion_evaluator.launch.xml | 3 + .../launch/planning_evaluator.launch.xml | 3 + .../autoware_planning_evaluator/package.xml | 1 + .../autoware_planning_evaluator.schema.json | 8 +- .../src/motion_evaluator_node.cpp | 56 +++++++++--- .../src/planning_evaluator_node.cpp | 88 ++++++++++++------- .../test/test_planning_evaluator_node.cpp | 3 +- 11 files changed, 121 insertions(+), 62 deletions(-) diff --git a/evaluator/autoware_planning_evaluator/README.md b/evaluator/autoware_planning_evaluator/README.md index 30ae1559ca9da..4fcdf4d7e55fd 100644 --- a/evaluator/autoware_planning_evaluator/README.md +++ b/evaluator/autoware_planning_evaluator/README.md @@ -62,8 +62,8 @@ Each metric is published on a topic named after the metric name. | ----------- | ------------------------------------- | ----------------------------------------------------------------- | | `~/metrics` | `tier4_metric_msgs::msg::MetricArray` | MetricArray with many metrics of `tier4_metric_msgs::msg::Metric` | -When shut down, the evaluation node writes the values of the metrics measured during its lifetime -to a file as specified by the `output_file` parameter. +If `output_metrics = true`, the evaluation node writes the statics of the metrics measured during its lifetime +to `/autoware_metrics/-.json` when shut down. ## Parameters diff --git a/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml b/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml index 2e92a174ca79f..14c1bcc6beea4 100644 --- a/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml +++ b/evaluator/autoware_planning_evaluator/config/planning_evaluator.param.yaml @@ -1,6 +1,5 @@ /**: ros__parameters: - output_file: "" # if empty, metrics are not written to file ego_frame: base_link # reference frame of ego selected_metrics: diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/motion_evaluator_node.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/motion_evaluator_node.hpp index 8193472c4dc39..7eed6e5645abc 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/motion_evaluator_node.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/motion_evaluator_node.hpp @@ -61,7 +61,7 @@ class MotionEvaluatorNode : public rclcpp::Node std::unique_ptr tf_listener_ptr_; // Parameters - std::string output_file_str_; + bool output_metrics_; // Calculator MetricsCalculator metrics_calculator_; diff --git a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp index 0f4b8f7289a4f..9c268206846d9 100644 --- a/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp +++ b/evaluator/autoware_planning_evaluator/include/autoware/planning_evaluator/planning_evaluator_node.hpp @@ -61,7 +61,7 @@ class PlanningEvaluatorNode : public rclcpp::Node { public: explicit PlanningEvaluatorNode(const rclcpp::NodeOptions & node_options); - ~PlanningEvaluatorNode(); + ~PlanningEvaluatorNode() override; /** * @brief callback on receiving an odometry @@ -97,17 +97,17 @@ class PlanningEvaluatorNode : public rclcpp::Node const Odometry::ConstSharedPtr ego_state_ptr); /** - * @brief publish the given metric statistic + * @brief add the given metric statistic */ void AddMetricMsg(const Metric & metric, const Accumulator & metric_stat); /** - * @brief publish current ego lane info + * @brief add current ego lane info */ void AddLaneletMetricMsg(const Odometry::ConstSharedPtr ego_state_ptr); /** - * @brief publish current ego kinematic state + * @brief add current ego kinematic state */ void AddKinematicStateMetricMsg( const AccelWithCovarianceStamped & accel_stamped, const Odometry::ConstSharedPtr ego_state_ptr); @@ -155,15 +155,15 @@ class PlanningEvaluatorNode : public rclcpp::Node MetricArrayMsg metrics_msg_; // Parameters - std::string output_file_str_; + bool output_metrics_; std::string ego_frame_str_; // Calculator MetricsCalculator metrics_calculator_; // Metrics std::vector metrics_; - std::deque stamps_; - std::array>, static_cast(Metric::SIZE)> metric_stats_; + std::array, 3>, static_cast(Metric::SIZE)> + metric_accumulators_; // 3(min, max, mean) * metric_size rclcpp::TimerBase::SharedPtr timer_; std::optional prev_acc_stamped_{std::nullopt}; diff --git a/evaluator/autoware_planning_evaluator/launch/motion_evaluator.launch.xml b/evaluator/autoware_planning_evaluator/launch/motion_evaluator.launch.xml index 6558d0b568c94..042d2458ae1da 100644 --- a/evaluator/autoware_planning_evaluator/launch/motion_evaluator.launch.xml +++ b/evaluator/autoware_planning_evaluator/launch/motion_evaluator.launch.xml @@ -1,7 +1,10 @@ + + + diff --git a/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml b/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml index 90c205dd55f1f..967668793a1e7 100644 --- a/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml +++ b/evaluator/autoware_planning_evaluator/launch/planning_evaluator.launch.xml @@ -1,4 +1,6 @@ + + @@ -12,6 +14,7 @@ + diff --git a/evaluator/autoware_planning_evaluator/package.xml b/evaluator/autoware_planning_evaluator/package.xml index 15d5d6da8504d..827784f71a823 100644 --- a/evaluator/autoware_planning_evaluator/package.xml +++ b/evaluator/autoware_planning_evaluator/package.xml @@ -22,6 +22,7 @@ eigen geometry_msgs nav_msgs + nlohmann-json-dev pluginlib rclcpp rclcpp_components diff --git a/evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json b/evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json index e7efbe06a8c00..1ef3874a0dcbc 100644 --- a/evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json +++ b/evaluator/autoware_planning_evaluator/schema/autoware_planning_evaluator.schema.json @@ -6,10 +6,10 @@ "autoware_planning_evaluator": { "type": "object", "properties": { - "output_file": { - "description": "output metrics file path", - "type": "string", - "default": "" + "output_metrics": { + "description": "If true, the evaluation node writes the metrics' statics to `/autoware_metrics/-.json` when the node shut down,", + "type": "boolean", + "default": "false" }, "ego_frame": { "description": "reference frame of ego", diff --git a/evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp index a5320ef28cbec..ac6f35179f771 100644 --- a/evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/motion_evaluator_node.cpp @@ -14,8 +14,11 @@ #include "autoware/planning_evaluator/motion_evaluator_node.hpp" +#include + +#include +#include #include -#include #include #include #include @@ -32,7 +35,7 @@ MotionEvaluatorNode::MotionEvaluatorNode(const rclcpp::NodeOptions & node_option "~/input/twist", rclcpp::QoS{1}, std::bind(&MotionEvaluatorNode::onOdom, this, std::placeholders::_1)); - output_file_str_ = declare_parameter("output_file"); + output_metrics_ = declare_parameter("output_metrics"); // List of metrics to calculate for (const std::string & selected_metric : @@ -44,22 +47,51 @@ MotionEvaluatorNode::MotionEvaluatorNode(const rclcpp::NodeOptions & node_option MotionEvaluatorNode::~MotionEvaluatorNode() { - // column width is the maximum size we might print + 1 for the space between columns - const auto column_width = 20; // std::to_string(std::numeric_limits::max()).size() + 1; - // Write data using format - std::ofstream f(output_file_str_); - f << std::fixed << std::left; - for (Metric metric : metrics_) { - f << std::setw(3 * column_width) << metric_descriptions.at(metric); + if (!output_metrics_) { + return; } - f << std::endl; + + // generate json data + using json = nlohmann::json; + json j; for (Metric metric : metrics_) { + const std::string base_name = metric_to_str.at(metric) + "/"; const auto & stat = metrics_calculator_.calculate(metric, accumulated_trajectory_); if (stat) { - f /* << std::setw(3 * column_width) */ << *stat << " "; + j[base_name + "min"] = stat->min(); + j[base_name + "max"] = stat->max(); + j[base_name + "mean"] = stat->mean(); } } - f.close(); + + // get output folder + const std::string output_folder_str = + rclcpp::get_logging_directory().string() + "/autoware_metrics"; + if (!std::filesystem::exists(output_folder_str)) { + if (!std::filesystem::create_directories(output_folder_str)) { + RCLCPP_ERROR( + this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); + return; + } + } + + // get time stamp + std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::tm * local_time = std::localtime(&now_time_t); + std::ostringstream oss; + oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); + std::string cur_time_str = oss.str(); + + // Write metrics .json to file + const std::string output_file_str = + output_folder_str + "/autoware_motion_evaluator-" + cur_time_str + ".json"; + std::ofstream f(output_file_str); + if (f.is_open()) { + f << j.dump(4); + f.close(); + } else { + RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); + } } void MotionEvaluatorNode::onOdom(const nav_msgs::msg::Odometry::SharedPtr msg) diff --git a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp index d770833bc40a8..da23c202312d7 100644 --- a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp @@ -16,13 +16,15 @@ #include #include +#include #include #include "boost/lexical_cast.hpp" +#include +#include #include -#include #include #include #include @@ -50,7 +52,7 @@ PlanningEvaluatorNode::PlanningEvaluatorNode(const rclcpp::NodeOptions & node_op metrics_calculator_.parameters.obstacle.dist_thr_m = declare_parameter("obstacle.dist_thr_m"); - output_file_str_ = declare_parameter("output_file"); + output_metrics_ = declare_parameter("output_metrics"); ego_frame_str_ = declare_parameter("ego_frame"); processing_time_pub_ = @@ -67,34 +69,49 @@ PlanningEvaluatorNode::PlanningEvaluatorNode(const rclcpp::NodeOptions & node_op PlanningEvaluatorNode::~PlanningEvaluatorNode() { - if (!output_file_str_.empty()) { - // column width is the maximum size we might print + 1 for the space between columns - // Write data using format - std::ofstream f(output_file_str_); - f << std::fixed << std::left; - // header - f << "#Stamp(ns)"; - for (Metric metric : metrics_) { - f << " " << metric_descriptions.at(metric); - f << " . ."; // extra "columns" to align columns headers - } - f << std::endl; - f << "#."; - for (Metric metric : metrics_) { - (void)metric; - f << " min max mean"; - } - f << std::endl; - // data - for (size_t i = 0; i < stamps_.size(); ++i) { - f << stamps_[i].nanoseconds(); - for (Metric metric : metrics_) { - const auto & stat = metric_stats_[static_cast(metric)][i]; - f << " " << stat; - } - f << std::endl; + if (!output_metrics_) { + return; + } + + // generate json data + using json = nlohmann::json; + json j; + for (Metric metric : metrics_) { + const std::string base_name = metric_to_str.at(metric) + "/"; + j[base_name + "min"] = metric_accumulators_[static_cast(metric)][0].min(); + j[base_name + "max"] = metric_accumulators_[static_cast(metric)][1].max(); + j[base_name + "mean"] = metric_accumulators_[static_cast(metric)][2].mean(); + j[base_name + "count"] = metric_accumulators_[static_cast(metric)][2].count(); + j[base_name + "description"] = metric_descriptions.at(metric); + } + + // get output folder + const std::string output_folder_str = + rclcpp::get_logging_directory().string() + "/autoware_metrics"; + if (!std::filesystem::exists(output_folder_str)) { + if (!std::filesystem::create_directories(output_folder_str)) { + RCLCPP_ERROR( + this->get_logger(), "Failed to create directories: %s", output_folder_str.c_str()); + return; } + } + + // get time stamp + std::time_t now_time_t = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); + std::tm * local_time = std::localtime(&now_time_t); + std::ostringstream oss; + oss << std::put_time(local_time, "%Y-%m-%d-%H-%M-%S"); + std::string cur_time_str = oss.str(); + + // Write metrics .json to file + const std::string output_file_str = + output_folder_str + "/autoware_planning_evaluator-" + cur_time_str + ".json"; + std::ofstream f(output_file_str); + if (f.is_open()) { + f << j.dump(4); f.close(); + } else { + RCLCPP_ERROR(this->get_logger(), "Failed to open file: %s", output_file_str.c_str()); } } @@ -269,9 +286,6 @@ void PlanningEvaluatorNode::onTrajectory( } auto start = now(); - if (!output_file_str_.empty()) { - stamps_.push_back(traj_msg->header.stamp); - } for (Metric metric : metrics_) { const auto metric_stat = metrics_calculator_.calculate(Metric(metric), *traj_msg); @@ -279,8 +293,10 @@ void PlanningEvaluatorNode::onTrajectory( continue; } - if (!output_file_str_.empty()) { - metric_stats_[static_cast(metric)].push_back(*metric_stat); + if (output_metrics_) { + metric_accumulators_[static_cast(metric)][0].add(metric_stat->min()); + metric_accumulators_[static_cast(metric)][1].add(metric_stat->max()); + metric_accumulators_[static_cast(metric)][2].add(metric_stat->mean()); } if (metric_stat->count() > 0) { @@ -308,7 +324,11 @@ void PlanningEvaluatorNode::onModifiedGoal( if (!metric_stat) { continue; } - metric_stats_[static_cast(metric)].push_back(*metric_stat); + if (output_metrics_) { + metric_accumulators_[static_cast(metric)][0].add(metric_stat->min()); + metric_accumulators_[static_cast(metric)][1].add(metric_stat->max()); + metric_accumulators_[static_cast(metric)][2].add(metric_stat->mean()); + } if (metric_stat->count() > 0) { AddMetricMsg(metric, *metric_stat); } diff --git a/evaluator/autoware_planning_evaluator/test/test_planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/test/test_planning_evaluator_node.cpp index ac99d164708ba..1b29edfb9b353 100644 --- a/evaluator/autoware_planning_evaluator/test/test_planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/test/test_planning_evaluator_node.cpp @@ -53,7 +53,8 @@ class EvalTest : public ::testing::Test const auto share_dir = ament_index_cpp::get_package_share_directory("autoware_planning_evaluator"); options.arguments( - {"--ros-args", "--params-file", share_dir + "/config/planning_evaluator.param.yaml"}); + {"--ros-args", "--params-file", share_dir + "/config/planning_evaluator.param.yaml", "-p", + "output_metrics:=false"}); dummy_node = std::make_shared("planning_evaluator_test_node"); eval_node = std::make_shared(options); From 22e85026d4592b0dcf56eab0dc0ac9c69cb3c013 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Fri, 29 Nov 2024 13:33:24 +0900 Subject: [PATCH 169/273] fix(dummy_perception_publisher): fix clang-diagnostic-unused-private-field (#9447) Signed-off-by: veqcc --- .../include/dummy_perception_publisher/node.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp b/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp index 4d50e547fc759..cf46ecddf516f 100644 --- a/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp +++ b/simulator/dummy_perception_publisher/include/dummy_perception_publisher/node.hpp @@ -124,7 +124,6 @@ class DummyPerceptionPublisherNode : public rclcpp::Node double detection_successful_rate_; bool enable_ray_tracing_; bool use_object_recognition_; - bool use_real_param_; bool use_base_link_z_; bool publish_ground_truth_objects_; std::unique_ptr pointcloud_creator_; From 42efae0886d43de092a22bb2ffea782d5b523814 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 29 Nov 2024 14:22:31 +0900 Subject: [PATCH 170/273] fix(autoware_lidar_centerpoint): fix clang-diagnostic-delete-abstract-non-virtual-dtor (#9515) Signed-off-by: kobayu858 --- .../autoware/lidar_centerpoint/preprocess/voxel_generator.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/voxel_generator.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/voxel_generator.hpp index 66384d192ae43..18d4f3abb3703 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/voxel_generator.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/preprocess/voxel_generator.hpp @@ -28,6 +28,7 @@ namespace autoware::lidar_centerpoint class VoxelGeneratorTemplate { public: + virtual ~VoxelGeneratorTemplate() = default; explicit VoxelGeneratorTemplate( const DensificationParam & param, const CenterPointConfig & config); From c8bc66d1d65b5599fc36c223f80dcc2c6525d711 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 29 Nov 2024 14:22:59 +0900 Subject: [PATCH 171/273] fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (#9495) Signed-off-by: kobayu858 --- .../roi_pointcloud_fusion/node.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp index c7cad2b5a64d0..4de49df61a071 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -49,7 +49,7 @@ class RoiPointCloudFusionNode const PointCloud2 & input_pointcloud_msg, const std::size_t image_id, const DetectedObjectsWithFeature & input_roi_msg, const sensor_msgs::msg::CameraInfo & camera_info, PointCloud2 & output_pointcloud_msg) override; - bool out_of_scope(const DetectedObjectWithFeature & obj); + bool out_of_scope(const DetectedObjectWithFeature & obj) override; }; } // namespace autoware::image_projection_based_fusion From 4c918a29b3d7d330d7e4c7e6cae046e067920aef Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 29 Nov 2024 14:23:19 +0900 Subject: [PATCH 172/273] fix(autoware_image_projection_based_fusion): fix clang-diagnostic-unused-private-field (#9505) Signed-off-by: kobayu858 --- .../autoware_image_projection_based_fusion/CMakeLists.txt | 1 - .../include/autoware/image_projection_based_fusion/debugger.hpp | 1 - .../autoware_image_projection_based_fusion/src/debugger.cpp | 2 +- 3 files changed, 1 insertion(+), 3 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/CMakeLists.txt b/perception/autoware_image_projection_based_fusion/CMakeLists.txt index 921a46ccebe3e..73d305d2ab2a8 100644 --- a/perception/autoware_image_projection_based_fusion/CMakeLists.txt +++ b/perception/autoware_image_projection_based_fusion/CMakeLists.txt @@ -2,7 +2,6 @@ cmake_minimum_required(VERSION 3.14) project(autoware_image_projection_based_fusion) # add_compile_options(-Wno-unknown-pragmas) add_compile_options(-Wno-unknown-pragmas -fopenmp) -add_compile_options(-Wno-error=attributes) find_package(autoware_cmake REQUIRED) find_package(OpenCV REQUIRED) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp index d74347772ef10..f4229382ba38c 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp @@ -56,7 +56,6 @@ class Debugger void imageCallback( const sensor_msgs::msg::Image::ConstSharedPtr input_image_msg, const std::size_t image_id); - [[maybe_unused]] rclcpp::Node * node_ptr_; std::shared_ptr image_transport_; std::vector input_camera_topics_; std::vector image_subs_; diff --git a/perception/autoware_image_projection_based_fusion/src/debugger.cpp b/perception/autoware_image_projection_based_fusion/src/debugger.cpp index 90952f3f6a8f5..975a3929ce77a 100644 --- a/perception/autoware_image_projection_based_fusion/src/debugger.cpp +++ b/perception/autoware_image_projection_based_fusion/src/debugger.cpp @@ -41,7 +41,7 @@ namespace autoware::image_projection_based_fusion Debugger::Debugger( rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size, std::vector input_camera_topics) -: node_ptr_(node_ptr), input_camera_topics_{input_camera_topics} +: input_camera_topics_{input_camera_topics} { image_buffers_.resize(image_num); image_buffer_size_ = image_buffer_size; From 996336fc51a3df332e7fc0466c56aaee4cc875f7 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Fri, 29 Nov 2024 14:23:51 +0900 Subject: [PATCH 173/273] fix(autoware_tensorrt_classifier): fix clang errors (#9508) Signed-off-by: kobayu858 --- .../include/autoware/tensorrt_classifier/calibrator.hpp | 8 ++++---- .../autoware/tensorrt_classifier/tensorrt_classifier.hpp | 1 - 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/calibrator.hpp b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/calibrator.hpp index 0977621894920..3d5d6f6538b15 100644 --- a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/calibrator.hpp +++ b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/calibrator.hpp @@ -270,19 +270,19 @@ class Int8LegacyCalibrator : public nvinfer1::IInt8LegacyCalibrator output.write(reinterpret_cast(cache), length); } - double getQuantile() const noexcept + double getQuantile() const noexcept override { printf("Quantile %f\n", m_quantile); return m_quantile; } - double getRegressionCutoff(void) const noexcept + double getRegressionCutoff(void) const noexcept override { printf("Cutoff %f\n", m_cutoff); return m_cutoff; } - const void * readHistogramCache(std::size_t & length) noexcept + const void * readHistogramCache(std::size_t & length) noexcept override { hist_cache_.clear(); std::ifstream input(histogram_cache_file_, std::ios::binary); @@ -301,7 +301,7 @@ class Int8LegacyCalibrator : public nvinfer1::IInt8LegacyCalibrator } return length ? &hist_cache_[0] : nullptr; } - void writeHistogramCache(void const * ptr, std::size_t length) noexcept + void writeHistogramCache(void const * ptr, std::size_t length) noexcept override { std::ofstream output(histogram_cache_file_, std::ios::binary); output.write(reinterpret_cast(ptr), length); diff --git a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp index 345e663441557..ee16343b956d1 100644 --- a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp +++ b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/tensorrt_classifier.hpp @@ -107,7 +107,6 @@ class TrtClassifier std::vector input_h_; CudaUniquePtr input_d_; - bool needs_output_decode_; size_t out_elem_num_; size_t out_elem_num_per_batch_; CudaUniquePtr out_prob_d_; From 70e4cd68dbc422bc65fcdbc399d02167be637857 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Fri, 29 Nov 2024 15:57:53 +0900 Subject: [PATCH 174/273] fix(lane_change): cap ego's predicted path velocity (RT1-8505) (#9341) * fix(lane_change): cap ego's predicted path velocity (RT1-8505) Signed-off-by: Zulfaqar Azmi * properly cap based on 0.0 instead of min lc vel Signed-off-by: Zulfaqar Azmi * fix build error Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi --- .../utils/utils.hpp | 7 ++- .../src/scene.cpp | 12 +---- .../src/utils/utils.cpp | 51 ++++++++++--------- 3 files changed, 32 insertions(+), 38 deletions(-) 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 2ec9d4cdf4e4e..7c1c8e2c65abe 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 @@ -116,10 +116,9 @@ CandidateOutput assignToCandidate( std::optional get_lane_change_target_lane( const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes); -std::vector convertToPredictedPath( - const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & pose, - const double lane_changing_acceleration, const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters, const double resolution); +std::vector convert_to_predicted_path( + const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, + const double lane_changing_acceleration); bool isParkedObject( const PathWithLaneId & path, const RouteHandler & route_handler, 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 1c2e6ba1c5b85..03c161d40d58a 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 @@ -1809,8 +1809,6 @@ bool NormalLaneChange::has_collision_with_decel_patterns( return false; } - const auto current_pose = common_data_ptr_->get_ego_pose(); - const auto current_twist = common_data_ptr_->get_ego_twist(); const auto bpp_param = *common_data_ptr_->bpp_param_ptr; const auto global_min_acc = bpp_param.min_acc; const auto lane_changing_acc = lane_change_path.info.longitudinal_acceleration.lane_changing; @@ -1827,17 +1825,11 @@ bool NormalLaneChange::has_collision_with_decel_patterns( acceleration_values.begin(), acceleration_values.end(), acceleration_values.begin(), [&](double n) { return lane_changing_acc + n * acc_resolution; }); - const auto time_resolution = - lane_change_parameters_->safety.collision_check.prediction_time_resolution; - const auto stopped_obj_vel_th = lane_change_parameters_->safety.th_stopped_object_velocity; const auto all_collided = std::all_of( acceleration_values.begin(), acceleration_values.end(), [&](const auto acceleration) { - const auto ego_predicted_path = utils::lane_change::convertToPredictedPath( - lane_change_path, current_twist, current_pose, acceleration, bpp_param, - *lane_change_parameters_, time_resolution); - const auto debug_predicted_path = - utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution); + const auto ego_predicted_path = utils::lane_change::convert_to_predicted_path( + common_data_ptr_, lane_change_path, acceleration); return std::any_of(objects.begin(), objects.end(), [&](const auto & obj) { const auto selected_rss_param = (obj.initial_twist.linear.x <= stopped_obj_vel_th) 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 db0c1cb37abbb..9ab6ac288dfd4 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 @@ -599,52 +599,55 @@ std::optional get_lane_change_target_lane( return route_handler_ptr->getLaneChangeTargetExceptPreferredLane(current_lanes, direction); } -std::vector convertToPredictedPath( - const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & vehicle_pose, - const double lane_changing_acceleration, const BehaviorPathPlannerParameters & common_parameters, - const LaneChangeParameters & lane_change_parameters, const double resolution) +std::vector convert_to_predicted_path( + const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path, + const double lane_changing_acceleration) { if (lane_change_path.path.points.empty()) { return {}; } const auto & path = lane_change_path.path; - const auto prepare_acc = lane_change_path.info.longitudinal_acceleration.prepare; - const auto duration = lane_change_path.info.duration.sum(); - const auto prepare_time = lane_change_path.info.duration.prepare; - const auto & minimum_lane_changing_velocity = - lane_change_parameters.trajectory.min_lane_changing_velocity; - + const auto & vehicle_pose = common_data_ptr->get_ego_pose(); + const auto & bpp_param_ptr = common_data_ptr->bpp_param_ptr; const auto nearest_seg_idx = autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints( - path.points, vehicle_pose, common_parameters.ego_nearest_dist_threshold, - common_parameters.ego_nearest_yaw_threshold); + path.points, vehicle_pose, bpp_param_ptr->ego_nearest_dist_threshold, + bpp_param_ptr->ego_nearest_yaw_threshold); - std::vector predicted_path; const auto vehicle_pose_frenet = convertToFrenetPoint(path.points, vehicle_pose.position, nearest_seg_idx); - const double initial_velocity = std::abs(vehicle_twist.linear.x); + + const auto initial_velocity = common_data_ptr->get_ego_speed(); + const auto prepare_acc = lane_change_path.info.longitudinal_acceleration.prepare; + const auto duration = lane_change_path.info.duration.sum(); + const auto prepare_time = lane_change_path.info.duration.prepare; + const auto & lc_param_ptr = common_data_ptr->lc_param_ptr; + const auto resolution = lc_param_ptr->safety.collision_check.prediction_time_resolution; + std::vector predicted_path; // prepare segment for (double t = 0.0; t < prepare_time; t += resolution) { - const double velocity = - std::max(initial_velocity + prepare_acc * t, minimum_lane_changing_velocity); - const double length = initial_velocity * t + 0.5 * prepare_acc * t * t; + const auto velocity = + std::clamp(initial_velocity + prepare_acc * t, 0.0, lane_change_path.info.velocity.prepare); + const auto length = initial_velocity * t + 0.5 * prepare_acc * t * t; const auto pose = autoware::motion_utils::calcInterpolatedPose( path.points, vehicle_pose_frenet.length + length); predicted_path.emplace_back(t, pose, velocity); } // lane changing segment - const double lane_changing_velocity = - std::max(initial_velocity + prepare_acc * prepare_time, minimum_lane_changing_velocity); - const double offset = + const auto lane_changing_velocity = std::clamp( + initial_velocity + prepare_acc * prepare_time, 0.0, lane_change_path.info.velocity.prepare); + const auto offset = initial_velocity * prepare_time + 0.5 * prepare_acc * prepare_time * prepare_time; for (double t = prepare_time; t < duration; t += resolution) { - const double delta_t = t - prepare_time; - const double velocity = lane_changing_velocity + lane_changing_acceleration * delta_t; - const double length = lane_changing_velocity * delta_t + - 0.5 * lane_changing_acceleration * delta_t * delta_t + offset; + const auto delta_t = t - prepare_time; + const auto velocity = std::clamp( + lane_changing_velocity + lane_changing_acceleration * delta_t, 0.0, + lane_change_path.info.velocity.lane_changing); + const auto length = lane_changing_velocity * delta_t + + 0.5 * lane_changing_acceleration * delta_t * delta_t + offset; const auto pose = autoware::motion_utils::calcInterpolatedPose( path.points, vehicle_pose_frenet.length + length); predicted_path.emplace_back(t, pose, velocity); From e4f84140cb497df51be67c86f8ed69946a9848bc Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Fri, 29 Nov 2024 17:20:28 +0900 Subject: [PATCH 175/273] feat(universe_utils): add extra info to time keeper warning (#9484) add extra info to time keeper warning Signed-off-by: Daniel Sanchez --- .github/{CODEOWNERS => _CODEOWNERS} | 0 .../autoware_universe_utils/src/system/time_keeper.cpp | 8 +++++--- .../test/src/system/test_time_keeper.cpp | 10 +++++++--- 3 files changed, 12 insertions(+), 6 deletions(-) rename .github/{CODEOWNERS => _CODEOWNERS} (100%) diff --git a/.github/CODEOWNERS b/.github/_CODEOWNERS similarity index 100% rename from .github/CODEOWNERS rename to .github/_CODEOWNERS diff --git a/common/autoware_universe_utils/src/system/time_keeper.cpp b/common/autoware_universe_utils/src/system/time_keeper.cpp index 8c715c5ccd7e3..b6e82cbd2f58a 100644 --- a/common/autoware_universe_utils/src/system/time_keeper.cpp +++ b/common/autoware_universe_utils/src/system/time_keeper.cpp @@ -20,6 +20,7 @@ #include #include +#include namespace autoware::universe_utils { @@ -135,9 +136,10 @@ void TimeKeeper::start_track(const std::string & func_name) root_node_thread_id_ = std::this_thread::get_id(); } else { if (root_node_thread_id_ != std::this_thread::get_id()) { - RCLCPP_WARN( - rclcpp::get_logger("TimeKeeper"), - "TimeKeeper::start_track() is called from a different thread. Ignoring the call."); + const auto warning_msg = fmt::format( + "TimeKeeper::start_track({}) is called from a different thread. Ignoring the call.", + func_name); + RCLCPP_WARN(rclcpp::get_logger("TimeKeeper"), "%s", warning_msg.c_str()); return; } current_time_node_ = current_time_node_->add_child(func_name); diff --git a/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp b/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp index 0540fa8a283ad..ffefaed316b19 100644 --- a/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp +++ b/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp @@ -86,7 +86,11 @@ TEST_F(TimeKeeperTest, MultiThreadWarning) t.join(); std::string err = testing::internal::GetCapturedStderr(); - EXPECT_TRUE( - err.find("TimeKeeper::start_track() is called from a different thread. Ignoring the call.") != - std::string::npos); + const bool error_found = err.find( + "TimeKeeper::start_track(MainFunction) is called from a different " + "thread. Ignoring the call.") != std::string::npos || + err.find( + "TimeKeeper::start_track(ThreadFunction) is called from a different " + "thread. Ignoring the call.") != std::string::npos; + EXPECT_TRUE(error_found); } From ac7fa10b948b2b789e05144266bfbea0fbee80be Mon Sep 17 00:00:00 2001 From: Tao Zhong <55872497+tzhong518@users.noreply.github.com> Date: Fri, 29 Nov 2024 23:05:40 +0900 Subject: [PATCH 176/273] fix(traffic_light_roi_visualizer): show unknown results correctly (#9467) fix: show unknown results correctly Signed-off-by: tzhong518 --- .../src/traffic_light_roi_visualizer/node.cpp | 8 +++++--- .../src/traffic_light_roi_visualizer/shape_draw.cpp | 7 +++++-- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/node.cpp b/perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/node.cpp index 7ef13cf457c07..6ab9f09064f58 100644 --- a/perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/node.cpp +++ b/perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/node.cpp @@ -201,9 +201,9 @@ void TrafficLightRoiVisualizerNode::imageRoughRoiCallback( // bbox drawing cv_ptr = cv_bridge::toCvCopy(input_image_msg, sensor_msgs::image_encodings::RGB8); for (auto tl_rough_roi : input_tl_rough_roi_msg->rois) { - // visualize rough roi - createRect(cv_ptr->image, tl_rough_roi, cv::Scalar(0, 255, 0)); - + // note: a signal will still be output even if it is undetected + // Its position and size will be set as 0 and the color will be set as unknown + // So a rough roi will always have correspond roi a correspond traffic signal ClassificationResult result; bool has_correspond_traffic_signal = getClassificationResult(tl_rough_roi.traffic_light_id, *input_traffic_signals_msg, result); @@ -211,6 +211,8 @@ void TrafficLightRoiVisualizerNode::imageRoughRoiCallback( bool has_correspond_roi = getRoiFromId(tl_rough_roi.traffic_light_id, input_tl_roi_msg, tl_roi); + createRect(cv_ptr->image, tl_rough_roi, extractShapeInfo(result.label).color); + if (has_correspond_roi && has_correspond_traffic_signal) { // has fine detection and classification results createRect(cv_ptr->image, tl_roi, result); 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 8c7a59cbcb003..d3ab30146a8b5 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 @@ -29,6 +29,10 @@ void drawShape( cv::Mat & image, const std::vector & params, int size, const cv::Point & position, const cv::Scalar & color, float probability) { + // skip if the roi position is set as (0,0), which means it is undetected + if (position.x == 0 && position.y == 0) { + return; + } // load concatenated shape image const auto shape_img = loadShapeImage(params, size); @@ -42,14 +46,13 @@ void drawShape( const int fill_rect_h = std::max(shape_img.rows, text_size.height) + 10; const cv::Point rect_position(position.x, position.y - fill_rect_h); - if ( rect_position.x < 0 || rect_position.y < 0 || rect_position.x + fill_rect_w > image.cols || position.y > image.rows) { // 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; + std::cerr << "Adjusted position is out of image bounds." << std::endl; return; } cv::Rect rectangle(rect_position.x, rect_position.y, fill_rect_w, fill_rect_h); From 0831075fc30465013f310e9d3e275fc9ae529c1a Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Fri, 29 Nov 2024 15:08:54 +0000 Subject: [PATCH 177/273] chore: sync files (#7568) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .clang-format | 4 ++ .github/ISSUE_TEMPLATE/bug.yaml | 4 ++ .github/ISSUE_TEMPLATE/config.yml | 4 ++ .github/ISSUE_TEMPLATE/task.yaml | 4 ++ .github/dependabot.yaml | 4 ++ .github/stale.yml | 4 ++ .../workflows/cancel-previous-workflows.yaml | 4 ++ .github/workflows/check-build-depends.yaml | 6 ++- .../clang-tidy-pr-comments-manually.yaml | 4 ++ .github/workflows/clang-tidy-pr-comments.yaml | 4 ++ .github/workflows/comment-on-pr.yaml | 4 ++ .github/workflows/delete-closed-pr-docs.yaml | 4 ++ .github/workflows/deploy-docs.yaml | 4 ++ .github/workflows/github-release.yaml | 4 ++ .github/workflows/pre-commit-autoupdate.yaml | 4 ++ .../pre-commit-optional-autoupdate.yaml | 41 +++++++++++++++++++ .github/workflows/pre-commit-optional.yaml | 4 ++ .github/workflows/pre-commit.yaml | 4 ++ .github/workflows/semantic-pull-request.yaml | 4 ++ .github/workflows/spell-check-daily.yaml | 7 ++++ .../workflows/spell-check-differential.yaml | 9 +++- .github/workflows/sync-files.yaml | 4 ++ .../update-codeowners-from-packages.yaml | 4 ++ .markdownlint.yaml | 4 ++ .pre-commit-config-optional.yaml | 4 ++ .pre-commit-config.yaml | 10 +++++ .prettierignore | 4 ++ .prettierrc.yaml | 4 ++ .yamllint.yaml | 4 ++ CPPLINT.cfg | 4 ++ docs/assets/js/mathjax.js | 4 ++ mkdocs.yaml | 4 ++ setup.cfg | 4 ++ 33 files changed, 183 insertions(+), 2 deletions(-) create mode 100644 .github/workflows/pre-commit-optional-autoupdate.yaml diff --git a/.clang-format b/.clang-format index b41fae9129e43..cd54eb45dde50 100644 --- a/.clang-format +++ b/.clang-format @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + # Modified from https://github.com/ament/ament_lint/blob/master/ament_clang_format/ament_clang_format/configuration/.clang-format Language: Cpp BasedOnStyle: Google diff --git a/.github/ISSUE_TEMPLATE/bug.yaml b/.github/ISSUE_TEMPLATE/bug.yaml index 12a857998a0b2..5c74f7c5e4d9c 100644 --- a/.github/ISSUE_TEMPLATE/bug.yaml +++ b/.github/ISSUE_TEMPLATE/bug.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: Bug description: Report a bug body: diff --git a/.github/ISSUE_TEMPLATE/config.yml b/.github/ISSUE_TEMPLATE/config.yml index 48765c24a7b25..deccbf336f6a3 100644 --- a/.github/ISSUE_TEMPLATE/config.yml +++ b/.github/ISSUE_TEMPLATE/config.yml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + blank_issues_enabled: false contact_links: - name: Question diff --git a/.github/ISSUE_TEMPLATE/task.yaml b/.github/ISSUE_TEMPLATE/task.yaml index cd8322f507405..58307325ce402 100644 --- a/.github/ISSUE_TEMPLATE/task.yaml +++ b/.github/ISSUE_TEMPLATE/task.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: Task description: Plan a task body: diff --git a/.github/dependabot.yaml b/.github/dependabot.yaml index 0264c035357bd..8fd9b7f4ae0a5 100644 --- a/.github/dependabot.yaml +++ b/.github/dependabot.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + version: 2 updates: - package-ecosystem: github-actions diff --git a/.github/stale.yml b/.github/stale.yml index bc99e4383cafd..ffce036c8d047 100644 --- a/.github/stale.yml +++ b/.github/stale.yml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + # Modified from https://github.com/probot/stale#usage # Number of days of inactivity before an Issue or Pull Request with the stale label is closed diff --git a/.github/workflows/cancel-previous-workflows.yaml b/.github/workflows/cancel-previous-workflows.yaml index bd2463d5a8eea..ee79ce0e4d41c 100644 --- a/.github/workflows/cancel-previous-workflows.yaml +++ b/.github/workflows/cancel-previous-workflows.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: cancel-previous-workflows on: diff --git a/.github/workflows/check-build-depends.yaml b/.github/workflows/check-build-depends.yaml index 74c97e3bf4be4..bb1d89851dea6 100644 --- a/.github/workflows/check-build-depends.yaml +++ b/.github/workflows/check-build-depends.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: check-build-depends on: @@ -20,7 +24,7 @@ jobs: build-depends-repos: build_depends.repos steps: - name: Check out repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 diff --git a/.github/workflows/clang-tidy-pr-comments-manually.yaml b/.github/workflows/clang-tidy-pr-comments-manually.yaml index a4df9f9dec3ed..747c62cdcd5a3 100644 --- a/.github/workflows/clang-tidy-pr-comments-manually.yaml +++ b/.github/workflows/clang-tidy-pr-comments-manually.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: clang-tidy-pr-comments-manually on: diff --git a/.github/workflows/clang-tidy-pr-comments.yaml b/.github/workflows/clang-tidy-pr-comments.yaml index bf2ed81d7ae48..c8df6a62c9a0a 100644 --- a/.github/workflows/clang-tidy-pr-comments.yaml +++ b/.github/workflows/clang-tidy-pr-comments.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: clang-tidy-pr-comments on: diff --git a/.github/workflows/comment-on-pr.yaml b/.github/workflows/comment-on-pr.yaml index c80141ddac6b0..0f2ecf519db11 100644 --- a/.github/workflows/comment-on-pr.yaml +++ b/.github/workflows/comment-on-pr.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: comment-on-pr on: pull_request_target: diff --git a/.github/workflows/delete-closed-pr-docs.yaml b/.github/workflows/delete-closed-pr-docs.yaml index 192e138a83c22..b8ff4f6d14599 100644 --- a/.github/workflows/delete-closed-pr-docs.yaml +++ b/.github/workflows/delete-closed-pr-docs.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: delete-closed-pr-docs on: diff --git a/.github/workflows/deploy-docs.yaml b/.github/workflows/deploy-docs.yaml index 771b4bd36ca9d..d39e97e540794 100644 --- a/.github/workflows/deploy-docs.yaml +++ b/.github/workflows/deploy-docs.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: deploy-docs on: diff --git a/.github/workflows/github-release.yaml b/.github/workflows/github-release.yaml index 4b1d7f47c6c0c..bbe2ac512d70d 100644 --- a/.github/workflows/github-release.yaml +++ b/.github/workflows/github-release.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: github-release on: diff --git a/.github/workflows/pre-commit-autoupdate.yaml b/.github/workflows/pre-commit-autoupdate.yaml index 8d57a53b5ccab..489e32a1de166 100644 --- a/.github/workflows/pre-commit-autoupdate.yaml +++ b/.github/workflows/pre-commit-autoupdate.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: pre-commit-autoupdate on: diff --git a/.github/workflows/pre-commit-optional-autoupdate.yaml b/.github/workflows/pre-commit-optional-autoupdate.yaml new file mode 100644 index 0000000000000..be79ad481d16e --- /dev/null +++ b/.github/workflows/pre-commit-optional-autoupdate.yaml @@ -0,0 +1,41 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + +name: pre-commit-optional-autoupdate + +on: + schedule: + - cron: 0 0 * * * + workflow_dispatch: + +jobs: + check-secret: + uses: autowarefoundation/autoware-github-actions/.github/workflows/check-secret.yaml@v1 + secrets: + secret: ${{ secrets.APP_ID }} + + pre-commit-optional-autoupdate: + needs: check-secret + if: ${{ needs.check-secret.outputs.set == 'true' }} + runs-on: ubuntu-22.04 + steps: + - name: Generate token + id: generate-token + uses: tibdex/github-app-token@v2 + with: + app_id: ${{ secrets.APP_ID }} + private_key: ${{ secrets.PRIVATE_KEY }} + + - name: Run pre-commit-autoupdate + uses: autowarefoundation/autoware-github-actions/pre-commit-autoupdate@v1 + with: + token: ${{ steps.generate-token.outputs.token }} + pre-commit-config: .pre-commit-config-optional.yaml + pr-labels: | + tag:bot + tag:pre-commit-autoupdate + pr-branch: pre-commit-optional-autoupdate + pr-title: "ci(pre-commit-optional): autoupdate" + pr-commit-message: "ci(pre-commit-optional): autoupdate" + auto-merge-method: squash diff --git a/.github/workflows/pre-commit-optional.yaml b/.github/workflows/pre-commit-optional.yaml index 12f536c551646..3d0867028f76a 100644 --- a/.github/workflows/pre-commit-optional.yaml +++ b/.github/workflows/pre-commit-optional.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: pre-commit-optional on: diff --git a/.github/workflows/pre-commit.yaml b/.github/workflows/pre-commit.yaml index 4d005e849b5ec..15c8e86c4f950 100644 --- a/.github/workflows/pre-commit.yaml +++ b/.github/workflows/pre-commit.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: pre-commit on: diff --git a/.github/workflows/semantic-pull-request.yaml b/.github/workflows/semantic-pull-request.yaml index 71224c224ec0f..b56040b084f0c 100644 --- a/.github/workflows/semantic-pull-request.yaml +++ b/.github/workflows/semantic-pull-request.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: semantic-pull-request on: diff --git a/.github/workflows/spell-check-daily.yaml b/.github/workflows/spell-check-daily.yaml index 8c0373594a90e..696963ff11cfd 100644 --- a/.github/workflows/spell-check-daily.yaml +++ b/.github/workflows/spell-check-daily.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: spell-check-daily on: @@ -18,3 +22,6 @@ jobs: local-cspell-json: .cspell.json incremental-files-only: false cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/.cspell.json + dict-packages: | + https://github.com/autowarefoundation/autoware-spell-check-dict + https://github.com/tier4/cspell-dicts diff --git a/.github/workflows/spell-check-differential.yaml b/.github/workflows/spell-check-differential.yaml index 3542659332532..81e3309365e9b 100644 --- a/.github/workflows/spell-check-differential.yaml +++ b/.github/workflows/spell-check-differential.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: spell-check-differential on: @@ -14,4 +18,7 @@ jobs: uses: autowarefoundation/autoware-github-actions/spell-check@v1 with: local-cspell-json: .cspell.json - cspell-json-url: https://raw.githubusercontent.com/tier4/autoware-spell-check-dict/main/.cspell.json + cspell-json-url: https://raw.githubusercontent.com/autowarefoundation/autoware-spell-check-dict/main/.cspell.json + dict-packages: | + https://github.com/autowarefoundation/autoware-spell-check-dict + https://github.com/tier4/cspell-dicts diff --git a/.github/workflows/sync-files.yaml b/.github/workflows/sync-files.yaml index 0cffbcd2a269f..9224c1503ed22 100644 --- a/.github/workflows/sync-files.yaml +++ b/.github/workflows/sync-files.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: sync-files on: diff --git a/.github/workflows/update-codeowners-from-packages.yaml b/.github/workflows/update-codeowners-from-packages.yaml index 760a647ffbf56..c9ecdb100688f 100644 --- a/.github/workflows/update-codeowners-from-packages.yaml +++ b/.github/workflows/update-codeowners-from-packages.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + name: update-codeowners-from-packages on: diff --git a/.markdownlint.yaml b/.markdownlint.yaml index 7b7359fe0cdc4..584154b2009de 100644 --- a/.markdownlint.yaml +++ b/.markdownlint.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + # See https://github.com/DavidAnson/markdownlint/blob/main/doc/Rules.md for all rules. default: true MD013: false diff --git a/.pre-commit-config-optional.yaml b/.pre-commit-config-optional.yaml index 8c9345e15f064..ff325af5e8774 100644 --- a/.pre-commit-config-optional.yaml +++ b/.pre-commit-config-optional.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + repos: - repo: https://github.com/tcort/markdown-link-check rev: v3.12.2 diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 63dc504f61a2b..e6dcc3f464ac7 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + ci: autofix_commit_msg: "style(pre-commit): autofix" @@ -93,3 +97,9 @@ repos: language: node files: .svg$ additional_dependencies: [prettier@2.7.1, "@prettier/plugin-xml@2.2.0"] + + - repo: https://github.com/AleksaC/hadolint-py + rev: v2.12.1b3 + hooks: + - id: hadolint + exclude: .svg$ diff --git a/.prettierignore b/.prettierignore index a3c34d00a1377..3e96aacebba60 100644 --- a/.prettierignore +++ b/.prettierignore @@ -1,2 +1,6 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + *.param.yaml *.rviz diff --git a/.prettierrc.yaml b/.prettierrc.yaml index e29bf32762769..fe476936f7b9e 100644 --- a/.prettierrc.yaml +++ b/.prettierrc.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + printWidth: 100 tabWidth: 2 overrides: diff --git a/.yamllint.yaml b/.yamllint.yaml index 2c7bd088e2648..e0be62dbcb16f 100644 --- a/.yamllint.yaml +++ b/.yamllint.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + extends: default ignore: | diff --git a/CPPLINT.cfg b/CPPLINT.cfg index ba6bdf08c10ca..81869c92be64c 100644 --- a/CPPLINT.cfg +++ b/CPPLINT.cfg @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + # Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_cpplint/ament_cpplint/main.py#L64-L120 set noparent linelength=100 diff --git a/docs/assets/js/mathjax.js b/docs/assets/js/mathjax.js index 117b04607f279..adb184a80399e 100644 --- a/docs/assets/js/mathjax.js +++ b/docs/assets/js/mathjax.js @@ -1,3 +1,7 @@ +// This file is automatically synced from: +// https://github.com/autowarefoundation/sync-file-templates +// To make changes, update the source repository and follow the guidelines in its README. + window.MathJax = { tex: { inlineMath: [["\\(", "\\)"]], diff --git a/mkdocs.yaml b/mkdocs.yaml index 2ca8b3c86ad43..38786709319be 100644 --- a/mkdocs.yaml +++ b/mkdocs.yaml @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + site_name: Autoware Universe Documentation site_url: https://autowarefoundation.github.io/autoware.universe repo_url: https://github.com/autowarefoundation/autoware.universe diff --git a/setup.cfg b/setup.cfg index 5214751c7ba6b..4d7d5e5b959d9 100644 --- a/setup.cfg +++ b/setup.cfg @@ -1,3 +1,7 @@ +# This file is automatically synced from: +# https://github.com/autowarefoundation/sync-file-templates +# To make changes, update the source repository and follow the guidelines in its README. + [flake8] # Modified from https://github.com/ament/ament_lint/blob/ebd524bb9973d5ec1dc48a670ce54f958a5a0243/ament_flake8/ament_flake8/configuration/ament_flake8.ini extend-ignore = B902,C816,D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404,I202,CNL100,E203,E501,Q000 From 9c5a0e1f8e3d6993dae7f538e0dfc113f10a5608 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Sat, 30 Nov 2024 17:05:01 +0000 Subject: [PATCH 178/273] chore: update CODEOWNERS (#9530) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * chore: update CODEOWNERS Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> * remove the misnamed file Signed-off-by: M. Fatih Cırıt --------- Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Signed-off-by: M. Fatih Cırıt Co-authored-by: github-actions Co-authored-by: M. Fatih Cırıt --- .github/{_CODEOWNERS => CODEOWNERS} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename .github/{_CODEOWNERS => CODEOWNERS} (100%) diff --git a/.github/_CODEOWNERS b/.github/CODEOWNERS similarity index 100% rename from .github/_CODEOWNERS rename to .github/CODEOWNERS From 99e88eed8db6a281079f006b264c918a8ef089be Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Sat, 30 Nov 2024 18:36:51 +0100 Subject: [PATCH 179/273] fix: fix package names in changelog files (#9500) Signed-off-by: Esteve Fernandez --- common/autoware_adapi_specs/CHANGELOG.rst | 6 +++--- common/autoware_component_interface_utils/CHANGELOG.rst | 6 +++--- common/autoware_fake_test_node/CHANGELOG.rst | 6 +++--- common/autoware_qp_interface/CHANGELOG.rst | 6 +++--- common/autoware_time_utils/CHANGELOG.rst | 6 +++--- .../CHANGELOG.rst | 6 +++--- common/autoware_traffic_light_utils/CHANGELOG.rst | 6 +++--- map/autoware_map_loader/CHANGELOG.rst | 6 +++--- sensing/autoware_cuda_utils/CHANGELOG.rst | 6 +++--- 9 files changed, 27 insertions(+), 27 deletions(-) diff --git a/common/autoware_adapi_specs/CHANGELOG.rst b/common/autoware_adapi_specs/CHANGELOG.rst index f94b51d97f949..b4fec15bfa98c 100644 --- a/common/autoware_adapi_specs/CHANGELOG.rst +++ b/common/autoware_adapi_specs/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_ad_api_specs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_adapi_specs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- diff --git a/common/autoware_component_interface_utils/CHANGELOG.rst b/common/autoware_component_interface_utils/CHANGELOG.rst index d27f4b4558bbc..d7f476f33409a 100644 --- a/common/autoware_component_interface_utils/CHANGELOG.rst +++ b/common/autoware_component_interface_utils/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package component_interface_utils -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_component_interface_utils +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- diff --git a/common/autoware_fake_test_node/CHANGELOG.rst b/common/autoware_fake_test_node/CHANGELOG.rst index 096c44f41ed77..330dddaa66aef 100644 --- a/common/autoware_fake_test_node/CHANGELOG.rst +++ b/common/autoware_fake_test_node/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package fake_test_node -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_fake_test_node +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- diff --git a/common/autoware_qp_interface/CHANGELOG.rst b/common/autoware_qp_interface/CHANGELOG.rst index b2e26a8e0085e..17e296bab4fca 100644 --- a/common/autoware_qp_interface/CHANGELOG.rst +++ b/common/autoware_qp_interface/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package qp_interface -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_qp_interface +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- diff --git a/common/autoware_time_utils/CHANGELOG.rst b/common/autoware_time_utils/CHANGELOG.rst index 73c72991895b0..43074de077e04 100644 --- a/common/autoware_time_utils/CHANGELOG.rst +++ b/common/autoware_time_utils/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package time_utils -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_time_utils +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- diff --git a/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst index d4f17b0feea0e..98691121f4d30 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst +++ b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package traffic_light_recognition_marker_publisher -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_traffic_light_recognition_marker_publisher +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- diff --git a/common/autoware_traffic_light_utils/CHANGELOG.rst b/common/autoware_traffic_light_utils/CHANGELOG.rst index 7a62fa661e9bb..d74774ae8ef3a 100644 --- a/common/autoware_traffic_light_utils/CHANGELOG.rst +++ b/common/autoware_traffic_light_utils/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package traffic_light_utils -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_traffic_light_utils +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- diff --git a/map/autoware_map_loader/CHANGELOG.rst b/map/autoware_map_loader/CHANGELOG.rst index d7acfba736fd1..8aafae5e8b44b 100644 --- a/map/autoware_map_loader/CHANGELOG.rst +++ b/map/autoware_map_loader/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package map_loader -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_map_loader +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- diff --git a/sensing/autoware_cuda_utils/CHANGELOG.rst b/sensing/autoware_cuda_utils/CHANGELOG.rst index f5437230cc80d..fe3b28768acbb 100644 --- a/sensing/autoware_cuda_utils/CHANGELOG.rst +++ b/sensing/autoware_cuda_utils/CHANGELOG.rst @@ -1,6 +1,6 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package cuda_utils -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_cuda_utils +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.38.0 (2024-11-08) ------------------- From 3cbca656980180b0d336592b3ad796d1414aa38f Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Sun, 1 Dec 2024 13:02:28 +0900 Subject: [PATCH 180/273] fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (#9509) Signed-off-by: kobayu858 --- .../segmentation_pointcloud_fusion/node.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp index 152829ea769d3..b09e9521bdcdb 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp @@ -62,7 +62,7 @@ class SegmentPointCloudFusionNode : public FusionNode Date: Sun, 1 Dec 2024 13:53:05 +0900 Subject: [PATCH 181/273] fix(autoware_bytetrack): fix clang-diagnostic-implicit-const-int-float-conversion (#9468) Signed-off-by: kobayu858 --- perception/autoware_bytetrack/lib/include/byte_tracker.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/perception/autoware_bytetrack/lib/include/byte_tracker.h b/perception/autoware_bytetrack/lib/include/byte_tracker.h index 60328c5acfd62..736ed6d311043 100644 --- a/perception/autoware_bytetrack/lib/include/byte_tracker.h +++ b/perception/autoware_bytetrack/lib/include/byte_tracker.h @@ -40,6 +40,7 @@ #include "strack.h" +#include #include struct ByteTrackObject @@ -83,8 +84,8 @@ class ByteTracker double lapjv( const std::vector> & cost, std::vector & rowsol, - std::vector & colsol, bool extend_cost = false, float cost_limit = LONG_MAX, - bool return_cost = true); + std::vector & colsol, bool extend_cost = false, + float cost_limit = std::numeric_limits::max(), bool return_cost = true); private: float track_thresh; From 4479e9433faf767ddc1607421f0f309b40d4f3dd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Sebastian=20Z=C4=99derowski?= Date: Mon, 2 Dec 2024 01:37:06 +0100 Subject: [PATCH 182/273] =?UTF-8?q?feat(object=5Flanelet=5Ffilter):=20add?= =?UTF-8?q?=20configurable=20margin=20for=20object=20lanel=E2=80=A6=20(#92?= =?UTF-8?q?40)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat(object_lanelet_filter): add configurable margin for object lanelet filter Signed-off-by: Sebastian Zęderowski modified: perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp Signed-off-by: Sebastian Zęderowski * feat(object_lanelet_filter): add condition to check wheter polygon is empty in debug mode Signed-off-by: Sebastian Zęderowski * feat(object_lanelet_filter): fix cppcheck Signed-off-by: Sebastian Zęderowski * fix: brig back missing type definition Signed-off-by: Taekjin LEE Signed-off-by: Sebastian Zęderowski * feat: add stop watch for processing time in object lanelet filter Signed-off-by: Taekjin LEE Signed-off-by: Sebastian Zęderowski * feat(object_lanelet_filter): remove extra comment line Signed-off-by: Sebastian Zęderowski * feat(_object_lanelet_filter): udpate readme Signed-off-by: Sebastian Zęderowski * style(pre-commit): autofix Signed-off-by: Sebastian Zęderowski * Update perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp Co-authored-by: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Signed-off-by: Sebastian Zęderowski * style(pre-commit): autofix Signed-off-by: Sebastian Zęderowski --------- Signed-off-by: Sebastian Zęderowski Signed-off-by: Taekjin LEE Co-authored-by: Sebastian Zęderowski Co-authored-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> --- .../CMakeLists.txt | 1 + .../config/object_lanelet_filter.param.yaml | 2 + .../object-lanelet-filter.md | 5 + .../src/lanelet_filter/debug.cpp | 128 ++++++++++++++++++ .../src/lanelet_filter/lanelet_filter.cpp | 87 ++++++++++-- .../src/lanelet_filter/lanelet_filter.hpp | 19 ++- 6 files changed, 231 insertions(+), 11 deletions(-) create mode 100644 perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp diff --git a/perception/autoware_detected_object_validation/CMakeLists.txt b/perception/autoware_detected_object_validation/CMakeLists.txt index 434c258918493..bf205fb32bb1d 100644 --- a/perception/autoware_detected_object_validation/CMakeLists.txt +++ b/perception/autoware_detected_object_validation/CMakeLists.txt @@ -48,6 +48,7 @@ target_link_libraries(obstacle_pointcloud_based_validator ) ament_auto_add_library(object_lanelet_filter SHARED + src/lanelet_filter/debug.cpp src/lanelet_filter/lanelet_filter.cpp lib/utils/utils.cpp ) diff --git a/perception/autoware_detected_object_validation/config/object_lanelet_filter.param.yaml b/perception/autoware_detected_object_validation/config/object_lanelet_filter.param.yaml index 99050d9738ae6..d15b2c81cf6db 100644 --- a/perception/autoware_detected_object_validation/config/object_lanelet_filter.param.yaml +++ b/perception/autoware_detected_object_validation/config/object_lanelet_filter.param.yaml @@ -19,3 +19,5 @@ enabled: false velocity_yaw_threshold: 0.785398 # [rad] (45 deg) object_speed_threshold: 3.0 # [m/s] + debug: false + lanelet_extra_margin: 0.0 diff --git a/perception/autoware_detected_object_validation/object-lanelet-filter.md b/perception/autoware_detected_object_validation/object-lanelet-filter.md index a14e28a42666d..b748885c188b4 100644 --- a/perception/autoware_detected_object_validation/object-lanelet-filter.md +++ b/perception/autoware_detected_object_validation/object-lanelet-filter.md @@ -24,6 +24,11 @@ The objects only inside of the vector map will be published. ## Parameters +| Name | Type | Description | +| ---------------------- | -------- | ------------------------------------------------------------------------------------ | +| `debug` | `bool` | if true, publish debug markers | +| `lanelet_extra_margin` | `double` | `if > 0` lanelet polygons are expanded by extra margin, `if <= 0` margin is disabled | + ### Core Parameters | Name | Type | Default Value | Description | diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp b/perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp new file mode 100644 index 0000000000000..b4116982f5b94 --- /dev/null +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp @@ -0,0 +1,128 @@ +// Copyright 2022 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 "lanelet_filter.hpp" + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace autoware::detected_object_validation +{ +namespace lanelet_filter +{ + +using visualization_msgs::msg::Marker; +using visualization_msgs::msg::MarkerArray; + +template +std::optional createPolygonMarker( + T polygon, rclcpp::Time stamp, std::string_view ns, size_t marker_id, + std_msgs::msg::ColorRGBA color) +{ + if (polygon.empty()) { + return std::nullopt; + } + const constexpr std::string_view FRAME_ID = "map"; + + auto create_marker = [&](auto marker_type) { + Marker marker; + marker.id = marker_id; + marker.header.frame_id = FRAME_ID; + marker.header.stamp = stamp; + marker.ns = ns; + marker.type = marker_type; + marker.action = Marker::ADD; + marker.lifetime = rclcpp::Duration::from_seconds(0.1); + return marker; + }; + + auto marker = create_marker(Marker::LINE_LIST); + marker.pose.orientation.w = 1.0; + marker.scale.x = 0.1; + marker.color.a = color.a; + marker.color.r = color.r; + marker.color.g = color.g; + marker.color.b = color.b; + + std::vector points; + points.reserve(polygon.size() * 2); + + for (auto it = polygon.begin(); it != std::prev(polygon.end()); ++it) { + geometry_msgs::msg::Point point; + + point.x = it->x(); + point.y = it->y(); + points.push_back(point); + + const auto next = std::next(it); + point.x = next->x(); + point.y = next->y(); + points.push_back(point); + } + geometry_msgs::msg::Point point; + point.x = polygon.back().x(); + point.y = polygon.back().y(); + + points.push_back(point); + point.x = polygon.front().x(); + point.y = polygon.front().y(); + + points.push_back(point); + marker.points = points; + return marker; +} + +void ObjectLaneletFilterNode::publishDebugMarkers( + rclcpp::Time stamp, const LinearRing2d & hull, const std::vector & lanelets) +{ + using visualization_msgs::msg::Marker; + using visualization_msgs::msg::MarkerArray; + + uint8_t marker_id = 0; + Marker delete_marker; + constexpr std::string_view lanelet_range = "lanelet_range"; + constexpr std::string_view roi = "roi"; + + MarkerArray marker_array; + + std_msgs::msg::ColorRGBA color; + color.a = 0.5f; + color.r = 0.3f; + color.g = 1.0f; + color.b = 0.2f; + if (auto marker = createPolygonMarker(hull, stamp, lanelet_range, ++marker_id, color); marker) { + marker_array.markers.push_back(std::move(*marker)); + } + for (const auto & box_and_lanelet : lanelets) { + color.r = 0.2; + color.g = 0.5; + color.b = 1.0; + auto p = box_and_lanelet.second.polygon; + if (auto marker = createPolygonMarker(p, stamp, roi, ++marker_id, color); marker) { + marker_array.markers.push_back(std::move(*marker)); + } + } + viz_pub_->publish(marker_array); +} +} // namespace lanelet_filter +} // namespace autoware::detected_object_validation diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp index e54ffd5452e7c..5e199a9ea9fad 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp @@ -59,6 +59,9 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod declare_parameter("filter_settings.lanelet_direction_filter.velocity_yaw_threshold"); filter_settings_.lanelet_direction_filter_object_speed_threshold = declare_parameter("filter_settings.lanelet_direction_filter.object_speed_threshold"); + filter_settings_.debug = declare_parameter("filter_settings.debug"); + filter_settings_.lanelet_extra_margin = + declare_parameter("filter_settings.lanelet_extra_margin"); // Set publisher/subscriber map_sub_ = this->create_subscription( @@ -73,6 +76,41 @@ ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & nod std::make_unique(this, "object_lanelet_filter"); published_time_publisher_ = std::make_unique(this); + stop_watch_ptr_ = + std::make_unique>(); + if (filter_settings_.debug) { + viz_pub_ = this->create_publisher( + "~/debug/marker", rclcpp::QoS{1}); + } +} + +bool isInPolygon( + const geometry_msgs::msg::Pose & current_pose, const lanelet::BasicPolygon2d & polygon, + const double radius) +{ + constexpr double eps = 1.0e-9; + const lanelet::BasicPoint2d p(current_pose.position.x, current_pose.position.y); + return boost::geometry::distance(p, polygon) < radius + eps; +} + +LinearRing2d expandPolygon(const LinearRing2d & polygon, double distance) +{ + universe_utils::MultiPolygon2d multi_polygon; + bg::strategy::buffer::distance_symmetric distance_strategy(distance); + bg::strategy::buffer::join_miter join_strategy; + bg::strategy::buffer::end_flat end_strategy; + bg::strategy::buffer::point_circle circle_strategy; + bg::strategy::buffer::side_straight side_strategy; + + bg::buffer( + polygon, multi_polygon, distance_strategy, side_strategy, join_strategy, end_strategy, + circle_strategy); + + if (multi_polygon.empty()) { + return polygon; + } + + return multi_polygon.front().outer(); } void ObjectLaneletFilterNode::mapCallback( @@ -86,6 +124,8 @@ void ObjectLaneletFilterNode::mapCallback( void ObjectLaneletFilterNode::objectCallback( const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr input_msg) { + stop_watch_ptr_->tic("processing_time"); + // Guard if (object_pub_->get_subscription_count() < 1) return; @@ -116,6 +156,9 @@ void ObjectLaneletFilterNode::objectCallback( local_rtree.insert(bbox_and_lanelet); } + if (filter_settings_.debug) { + publishDebugMarkers(input_msg->header.stamp, convex_hull, intersected_lanelets_with_bbox); + } // filtering process for (size_t index = 0; index < transformed_objects.objects.size(); ++index) { const auto & transformed_object = transformed_objects.objects.at(index); @@ -135,6 +178,8 @@ void ObjectLaneletFilterNode::objectCallback( .count(); debug_publisher_->publish( "debug/pipeline_latency_ms", pipeline_latency); + debug_publisher_->publish( + "debug/processing_time_ms", stop_watch_ptr_->toc("processing_time", true)); } bool ObjectLaneletFilterNode::filterObject( @@ -217,6 +262,9 @@ LinearRing2d ObjectLaneletFilterNode::getConvexHull( LinearRing2d convex_hull; bg::convex_hull(candidate_points, convex_hull); + if (filter_settings_.lanelet_extra_margin > 0) { + return expandPolygon(convex_hull, filter_settings_.lanelet_extra_margin); + } return convex_hull; } @@ -265,12 +313,12 @@ std::vector ObjectLaneletFilterNode::getIntersectedLanelets( lanelet.attribute(lanelet::AttributeName::Subtype).value() == "road_shoulder")) { if (bg::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) { // create bbox using boost for making the R-tree in later phase - lanelet::BoundingBox2d lanelet_bbox = lanelet::geometry::boundingBox2d(lanelet); - Point2d min_corner(lanelet_bbox.min().x(), lanelet_bbox.min().y()); - Point2d max_corner(lanelet_bbox.max().x(), lanelet_bbox.max().y()); - Box boost_bbox(min_corner, max_corner); + auto polygon = getPolygon(lanelet); + Box boost_bbox; + bg::envelope(polygon, boost_bbox); - intersected_lanelets_with_bbox.emplace_back(std::make_pair(boost_bbox, lanelet)); + intersected_lanelets_with_bbox.emplace_back( + std::make_pair(boost_bbox, PolygonAndLanelet{polygon, lanelet})); } } } @@ -278,6 +326,25 @@ std::vector ObjectLaneletFilterNode::getIntersectedLanelets( return intersected_lanelets_with_bbox; } +lanelet::BasicPolygon2d ObjectLaneletFilterNode::getPolygon(const lanelet::ConstLanelet & lanelet) +{ + if (filter_settings_.lanelet_extra_margin <= 0) { + return lanelet.polygon2d().basicPolygon(); + } + + auto lanelet_polygon = lanelet.polygon2d().basicPolygon(); + Polygon2d polygon; + bg::assign_points(polygon, lanelet_polygon); + + bg::correct(polygon); + auto polygon_result = expandPolygon(polygon.outer(), filter_settings_.lanelet_extra_margin); + lanelet::BasicPolygon2d result; + + bg::assign_points(result, polygon_result); + + return result; +} + bool ObjectLaneletFilterNode::isObjectOverlapLanelets( const autoware_perception_msgs::msg::DetectedObject & object, const bgi::rtree & local_rtree) @@ -314,7 +381,7 @@ bool ObjectLaneletFilterNode::isObjectOverlapLanelets( point2d.position.y = point_transformed.y; for (const auto & candidate : candidates) { - if (lanelet::utils::isInLanelet(point2d, candidate.second, 0.0)) { + if (isInPolygon(point2d, candidate.second.polygon, 0.0)) { return true; } } @@ -334,7 +401,7 @@ bool ObjectLaneletFilterNode::isPolygonOverlapLanelets( local_rtree.query(bgi::intersects(bbox_of_convex_hull), std::back_inserter(candidates)); for (const auto & box_and_lanelet : candidates) { - if (!bg::disjoint(polygon, box_and_lanelet.second.polygon2d().basicPolygon())) { + if (!bg::disjoint(polygon, box_and_lanelet.second.polygon)) { return true; } } @@ -374,14 +441,14 @@ bool ObjectLaneletFilterNode::isSameDirectionWithLanelets( local_rtree.query(bgi::intersects(bbox), std::back_inserter(candidates)); for (const auto & box_and_lanelet : candidates) { - const bool is_in_lanelet = lanelet::utils::isInLanelet( - object.kinematics.pose_with_covariance.pose, box_and_lanelet.second, 0.0); + const bool is_in_lanelet = + isInPolygon(object.kinematics.pose_with_covariance.pose, box_and_lanelet.second.polygon, 0.0); if (!is_in_lanelet) { continue; } const double lane_yaw = lanelet::utils::getLaneletAngle( - box_and_lanelet.second, object.kinematics.pose_with_covariance.pose.position); + box_and_lanelet.second.lanelet, object.kinematics.pose_with_covariance.pose.position); const double delta_yaw = object_velocity_yaw - lane_yaw; const double normalized_delta_yaw = autoware::universe_utils::normalizeRadian(delta_yaw); const double abs_norm_delta_yaw = std::fabs(normalized_delta_yaw); diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.hpp b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.hpp index 05020336bc759..724e60df27e49 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.hpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.hpp @@ -19,12 +19,14 @@ #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/ros/debug_publisher.hpp" #include "autoware/universe_utils/ros/published_time_publisher.hpp" +#include "autoware/universe_utils/system/stop_watch.hpp" #include "autoware_lanelet2_extension/utility/utilities.hpp" #include #include "autoware_map_msgs/msg/lanelet_map_bin.hpp" #include "autoware_perception_msgs/msg/detected_objects.hpp" +#include #include @@ -50,7 +52,13 @@ namespace bg = boost::geometry; namespace bgi = boost::geometry::index; using Point2d = bg::model::point; using Box = boost::geometry::model::box; -using BoxAndLanelet = std::pair; + +struct PolygonAndLanelet +{ + lanelet::BasicPolygon2d polygon; + lanelet::ConstLanelet lanelet; +}; +using BoxAndLanelet = std::pair; using RtreeAlgo = bgi::rstar<16>; class ObjectLaneletFilterNode : public rclcpp::Node @@ -62,10 +70,16 @@ class ObjectLaneletFilterNode : public rclcpp::Node void objectCallback(const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr); void mapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr); + void publishDebugMarkers( + rclcpp::Time stamp, const LinearRing2d & hull, const std::vector & lanelets); + rclcpp::Publisher::SharedPtr object_pub_; + rclcpp::Publisher::SharedPtr viz_pub_; rclcpp::Subscription::SharedPtr map_sub_; rclcpp::Subscription::SharedPtr object_sub_; + std::unique_ptr debug_publisher_{nullptr}; + std::unique_ptr> stop_watch_ptr_; lanelet::LaneletMapPtr lanelet_map_ptr_; std::string lanelet_frame_id_; @@ -80,6 +94,8 @@ class ObjectLaneletFilterNode : public rclcpp::Node bool lanelet_direction_filter; double lanelet_direction_filter_velocity_yaw_threshold; double lanelet_direction_filter_object_speed_threshold; + bool debug; + double lanelet_extra_margin; } filter_settings_; bool filterObject( @@ -101,6 +117,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node const bgi::rtree & local_rtree); geometry_msgs::msg::Polygon setFootprint(const autoware_perception_msgs::msg::DetectedObject &); + lanelet::BasicPolygon2d getPolygon(const lanelet::ConstLanelet & lanelet); std::unique_ptr published_time_publisher_; }; From 889b6494ab6d757286ed62e340ba5c40541dc4d4 Mon Sep 17 00:00:00 2001 From: Go Sakayori Date: Mon, 2 Dec 2024 10:15:30 +0900 Subject: [PATCH 183/273] feat(velocity_smoother, external_velocity_limit_selector): enable stronger acceleration when requested (#9502) * change max acceleration and max jerk according to external velocity request Signed-off-by: Go Sakayori * modify external velocity limit selector Signed-off-by: Go Sakayori * fix external velocity limit selector Signed-off-by: Go Sakayori * fix format Signed-off-by: Go Sakayori --------- Signed-off-by: Go Sakayori Signed-off-by: Go Sakayori --- .../external_velocity_limit_selector_node.hpp | 1 - .../external_velocity_limit_selector_node.cpp | 30 ++++++++++++++- .../autoware/velocity_smoother/node.hpp | 7 ++++ .../smoother/smoother_base.hpp | 2 + .../autoware_velocity_smoother/src/node.cpp | 38 +++++++++++++++++-- .../src/smoother/smoother_base.cpp | 10 +++++ 6 files changed, 81 insertions(+), 7 deletions(-) diff --git a/planning/autoware_external_velocity_limit_selector/include/autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp b/planning/autoware_external_velocity_limit_selector/include/autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp index 2aa06079dadbc..6a8fae3bf394c 100644 --- a/planning/autoware_external_velocity_limit_selector/include/autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp +++ b/planning/autoware_external_velocity_limit_selector/include/autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp @@ -22,7 +22,6 @@ #include #include -#include #include #include #include diff --git a/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp b/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp index 2052c8438bcfa..cf42763fc6b60 100644 --- a/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp +++ b/planning/autoware_external_velocity_limit_selector/src/external_velocity_limit_selector_node.cpp @@ -14,12 +14,12 @@ #include "autoware/external_velocity_limit_selector/external_velocity_limit_selector_node.hpp" -#include +#include #include +#include #include #include #include -#include namespace autoware::external_velocity_limit_selector { @@ -34,12 +34,17 @@ VelocityLimit getHardestLimit( hardest_limit.max_velocity = node_param.max_vel; VelocityLimitConstraints normal_constraints{}; + normal_constraints.max_acceleration = node_param.normal.max_acc; normal_constraints.min_acceleration = node_param.normal.min_acc; normal_constraints.min_jerk = node_param.normal.min_jerk; normal_constraints.max_jerk = node_param.normal.max_jerk; double hardest_max_velocity = node_param.max_vel; double hardest_max_jerk = 0.0; + double hardest_max_acceleration = 0.0; + std::string hardest_max_acceleration_key; + size_t constraint_num = 0; + size_t acceleration_constraint_num = 0; for (const auto & limit : velocity_limits) { // guard nan, inf @@ -59,6 +64,19 @@ VelocityLimit getHardestLimit( ? limit.second.constraints : normal_constraints; + if (limit.second.use_constraints) { + constraint_num++; + if (limit.second.constraints.max_acceleration > normal_constraints.max_acceleration) { + acceleration_constraint_num++; + hardest_max_acceleration_key = limit.first; + } + } + + if (hardest_max_acceleration < limit.second.constraints.max_acceleration) { + hardest_max_acceleration_key = limit.first; + hardest_max_acceleration = limit.second.constraints.max_acceleration; + } + // find hardest jerk if (hardest_max_jerk < constraints.max_jerk) { hardest_limit.constraints = constraints; @@ -67,6 +85,14 @@ VelocityLimit getHardestLimit( } } + if (constraint_num > 0 && constraint_num == acceleration_constraint_num) { + if (velocity_limits.find(hardest_max_acceleration_key) != velocity_limits.end()) { + const auto constraints = velocity_limits.at(hardest_max_acceleration_key).constraints; + hardest_limit.constraints = constraints; + hardest_limit.use_constraints = true; + } + } + return hardest_limit; } diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp index 3f1c313e052da..069363d2f65e0 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/node.hpp @@ -164,10 +164,17 @@ class VelocitySmootherNode : public rclcpp::Node bool plan_from_ego_speed_on_manual_mode = true; } node_param_{}; + struct AccelerationRequest + { + bool request{false}; + double max_acceleration{0.0}; + double max_jerk{0.0}; + }; struct ExternalVelocityLimit { double velocity{0.0}; // current external_velocity_limit double dist{0.0}; // distance to set external velocity limit + AccelerationRequest acceleration_request; std::string sender{""}; }; ExternalVelocityLimit diff --git a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp index 7206a64ea32eb..d51431383f88a 100644 --- a/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp +++ b/planning/autoware_velocity_smoother/include/autoware/velocity_smoother/smoother/smoother_base.hpp @@ -83,6 +83,8 @@ class SmootherBase double getMinJerk() const; void setWheelBase(const double wheel_base); + void setMaxAccel(const double max_acceleration); + void setMaxJerk(const double max_jerk); void setParam(const BaseParam & param); BaseParam getBaseParam() const; diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index a358a1b61c11b..f47c84ab54b01 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -319,6 +319,7 @@ void VelocitySmootherNode::calcExternalVelocityLimit() autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (!external_velocity_limit_ptr_) { + external_velocity_limit_.acceleration_request.request = false; return; } @@ -342,6 +343,20 @@ void VelocitySmootherNode::calcExternalVelocityLimit() external_velocity_limit_.dist = 0.0; } + const auto base_max_acceleration = get_parameter("normal.max_acc").as_double(); + const auto acceleration_request = + external_velocity_limit_ptr_->use_constraints && + base_max_acceleration < external_velocity_limit_ptr_->constraints.max_acceleration; + if ( + acceleration_request && + current_odometry_ptr_->twist.twist.linear.x < external_velocity_limit_ptr_->max_velocity) { + external_velocity_limit_.acceleration_request.request = true; + external_velocity_limit_.acceleration_request.max_acceleration = + external_velocity_limit_ptr_->constraints.max_acceleration; + external_velocity_limit_.acceleration_request.max_jerk = + external_velocity_limit_ptr_->constraints.max_jerk; + } + // calculate distance and maximum velocity // to decelerate to external velocity limit with jerk and acceleration // constraints. @@ -627,6 +642,18 @@ bool VelocitySmootherNode::smoothVelocity( clipped.insert( clipped.end(), traj_resampled.begin() + traj_resampled_closest, traj_resampled.end()); + // Set maximum acceleration before applying smoother. Depends on acceleration request from + // external velocity limit + const double smoother_max_acceleration = + external_velocity_limit_.acceleration_request.request + ? external_velocity_limit_.acceleration_request.max_acceleration + : get_parameter("normal.max_acc").as_double(); + const double smoother_max_jerk = external_velocity_limit_.acceleration_request.request + ? external_velocity_limit_.acceleration_request.max_jerk + : get_parameter("normal.max_jerk").as_double(); + smoother_->setMaxAccel(smoother_max_acceleration); + smoother_->setMaxJerk(smoother_max_jerk); + std::vector debug_trajectories; if (!smoother_->apply( initial_motion.vel, initial_motion.acc, clipped, traj_smoothed, debug_trajectories, @@ -791,12 +818,15 @@ std::pair VelocitySmootherNode::ca "calcInitialMotion : vehicle speed is low (%.3f), and desired speed is high (%.3f). Use " "engage speed (%.3f) until vehicle speed reaches engage_vel_thr (%.3f). stop_dist = %.3f", vehicle_speed, target_vel, node_param_.engage_velocity, engage_vel_thr, stop_dist); - Motion initial_motion = {node_param_.engage_velocity, node_param_.engage_acceleration}; + const double engage_acceleration = + external_velocity_limit_.acceleration_request.request + ? external_velocity_limit_.acceleration_request.max_acceleration + : node_param_.engage_acceleration; + Motion initial_motion = {node_param_.engage_velocity, engage_acceleration}; return {initial_motion, InitializeType::ENGAGING}; - } else { - RCLCPP_DEBUG( - get_logger(), "calcInitialMotion : stop point is close (%.3f[m]). no engage.", stop_dist); } + RCLCPP_DEBUG( + get_logger(), "calcInitialMotion : stop point is close (%.3f[m]). no engage.", stop_dist); } else if (target_vel > 0.0) { RCLCPP_WARN_THROTTLE( get_logger(), *clock_, 3000, diff --git a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp index 46faf10fe4a62..5360da101ee8c 100644 --- a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp @@ -97,6 +97,16 @@ void SmootherBase::setWheelBase(const double wheel_base) base_param_.wheel_base = wheel_base; } +void SmootherBase::setMaxAccel(const double max_acceleration) +{ + base_param_.max_accel = max_acceleration; +} + +void SmootherBase::setMaxJerk(const double max_jerk) +{ + base_param_.max_jerk = max_jerk; +} + void SmootherBase::setParam(const BaseParam & param) { base_param_ = param; From df241f7b73cc9dafb6fbe2d0c53ebc9a097aaca1 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 2 Dec 2024 10:37:39 +0900 Subject: [PATCH 184/273] fix(autoware_ground_segmentation): fix clang-diagnostic-inconsistent-missing-override (#9517) * fix: clang-diagnostic-inconsistent-missing-override Signed-off-by: kobayu858 * fix: pre-commit error Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../src/scan_ground_filter/node.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) 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 62db8307a0a37..41c41f1899163 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/node.hpp @@ -146,9 +146,9 @@ class ScanGroundFilterComponent : public autoware::pointcloud_preprocessor::Filt // TODO(taisa1): Temporary Implementation: Remove this interface when all the filter nodes // conform to new API - virtual void faster_filter( + void faster_filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output, - const autoware::pointcloud_preprocessor::TransformInfo & transform_info); + const autoware::pointcloud_preprocessor::TransformInfo & transform_info) override; tf2_ros::Buffer tf_buffer_{get_clock()}; tf2_ros::TransformListener tf_listener_{tf_buffer_}; From adb6101080c408d0899c6fead712b1311854bfbb Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Mon, 2 Dec 2024 10:38:37 +0900 Subject: [PATCH 185/273] fix(autoware_bytetrack): fix clang-diagnostic-implicit-const-int-float-conversion (#9513) fix: clang-diagnostic-implicit-const-int-float-conversion Signed-off-by: kobayu858 --- perception/autoware_bytetrack/lib/src/utils.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/perception/autoware_bytetrack/lib/src/utils.cpp b/perception/autoware_bytetrack/lib/src/utils.cpp index e987bd36b8064..d9ff5af52f6bf 100644 --- a/perception/autoware_bytetrack/lib/src/utils.cpp +++ b/perception/autoware_bytetrack/lib/src/utils.cpp @@ -40,6 +40,7 @@ #include "lapjv.h" #include +#include std::vector ByteTracker::joint_stracks( std::vector & tlista, std::vector & tlistb) @@ -292,14 +293,14 @@ double ByteTracker::lapjv( } } - if (extend_cost || cost_limit < LONG_MAX) { + if (extend_cost || cost_limit < std::numeric_limits::max()) { std::vector> cost_c_extended; n = n_rows + n_cols; cost_c_extended.resize(n); for (size_t i = 0; i < cost_c_extended.size(); i++) cost_c_extended[i].resize(n); - if (cost_limit < LONG_MAX) { + if (cost_limit < std::numeric_limits::max()) { for (size_t i = 0; i < cost_c_extended.size(); i++) { for (size_t j = 0; j < cost_c_extended[i].size(); j++) { cost_c_extended[i][j] = cost_limit / 2.0; From 421dcfcef8a7fd1f3e293003bdabf443fff573c7 Mon Sep 17 00:00:00 2001 From: Mukunda Bharatheesha Date: Mon, 2 Dec 2024 03:05:47 +0100 Subject: [PATCH 186/273] fix(autoware_pointcloud_preprocessor): remove unused arg and unavailable param file. (#9525) Remove unused arg and unavailable param file. Signed-off-by: Mukunda Bharatheesha --- .../launch/approximate_downsample_filter.launch.xml | 2 -- .../launch/crop_box_filter_node.launch.xml | 2 -- .../launch/dual_return_outlier_filter_node.launch.xml | 2 -- .../pickup_based_voxel_grid_downsample_filter_node.launch.xml | 2 -- .../launch/pointcloud_accumulator_node.launch.xml | 2 -- .../launch/radius_search_2d_outlier_filter_node.launch.xml | 2 -- .../launch/random_downsample_filter_node.launch.xml | 2 -- .../launch/ring_outlier_filter_node.launch.xml | 2 -- .../launch/ring_passthrough_filter.launch.xml | 2 -- .../launch/vector_map_inside_area_filter_node.launch.xml | 2 -- .../launch/voxel_grid_downsample_filter_node.launch.xml | 2 -- .../launch/voxel_grid_outlier_filter_node.launch.xml | 2 -- 12 files changed, 24 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/launch/approximate_downsample_filter.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/approximate_downsample_filter.launch.xml index f4375e5a5cd2f..8912847ce1e4a 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/approximate_downsample_filter.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/approximate_downsample_filter.launch.xml @@ -4,10 +4,8 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/crop_box_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/crop_box_filter_node.launch.xml index bb07daf8841b9..4cb9c9412df00 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/crop_box_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/crop_box_filter_node.launch.xml @@ -3,11 +3,9 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter_node.launch.xml index d0293ca140e4f..5c79787a58e9e 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/dual_return_outlier_filter_node.launch.xml @@ -4,11 +4,9 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/pickup_based_voxel_grid_downsample_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/pickup_based_voxel_grid_downsample_filter_node.launch.xml index 7c035cbcf1b52..83c0fe9a20d4c 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/pickup_based_voxel_grid_downsample_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/pickup_based_voxel_grid_downsample_filter_node.launch.xml @@ -4,10 +4,8 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/pointcloud_accumulator_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/pointcloud_accumulator_node.launch.xml index 3f132a1586a36..1305ce5992866 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/pointcloud_accumulator_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/pointcloud_accumulator_node.launch.xml @@ -4,10 +4,8 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/radius_search_2d_outlier_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/radius_search_2d_outlier_filter_node.launch.xml index 665c8d7c6e37c..cdd1f8589f3e3 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/radius_search_2d_outlier_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/radius_search_2d_outlier_filter_node.launch.xml @@ -4,10 +4,8 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/random_downsample_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/random_downsample_filter_node.launch.xml index 4663cece6ea60..12109ffec5b38 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/random_downsample_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/random_downsample_filter_node.launch.xml @@ -4,11 +4,9 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/ring_outlier_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/ring_outlier_filter_node.launch.xml index 68076f5c9c321..df45e81653303 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/ring_outlier_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/ring_outlier_filter_node.launch.xml @@ -3,11 +3,9 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml index 800fa5f3ec3ee..36f30fc2d41ee 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/ring_passthrough_filter.launch.xml @@ -4,11 +4,9 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml index 795234e185cdd..f5980b0814edc 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/vector_map_inside_area_filter_node.launch.xml @@ -3,10 +3,8 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/voxel_grid_downsample_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/voxel_grid_downsample_filter_node.launch.xml index f674e8d9dfa14..90a2b9993fc18 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/voxel_grid_downsample_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/voxel_grid_downsample_filter_node.launch.xml @@ -4,10 +4,8 @@ - - diff --git a/sensing/autoware_pointcloud_preprocessor/launch/voxel_grid_outlier_filter_node.launch.xml b/sensing/autoware_pointcloud_preprocessor/launch/voxel_grid_outlier_filter_node.launch.xml index 380a46eed3159..e1b963922a2ff 100644 --- a/sensing/autoware_pointcloud_preprocessor/launch/voxel_grid_outlier_filter_node.launch.xml +++ b/sensing/autoware_pointcloud_preprocessor/launch/voxel_grid_outlier_filter_node.launch.xml @@ -4,10 +4,8 @@ - - From 8476e34a899d3741abf8bb7d95a339d92c0bb820 Mon Sep 17 00:00:00 2001 From: Kazunori-Nakajima <169115284+Kazunori-Nakajima@users.noreply.github.com> Date: Mon, 2 Dec 2024 11:56:03 +0900 Subject: [PATCH 187/273] fix(control_evaluator): correct goal_lateal_deviation (#9532) Signed-off-by: Kasunori-Nakajima --- .../autoware_control_evaluator/src/control_evaluator_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp index 2a2c07b2db319..9c8579469f878 100644 --- a/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp @@ -232,7 +232,7 @@ void ControlEvaluatorNode::AddGoalLongitudinalDeviationMetricMsg(const Pose & eg void ControlEvaluatorNode::AddGoalLateralDeviationMetricMsg(const Pose & ego_pose) { - const Metric metric = Metric::lateral_deviation; + const Metric metric = Metric::goal_lateral_deviation; const double metric_value = metrics::calcLateralDeviation(route_handler_.getGoalPose(), ego_pose.position); From 815abd93a997812a853c8b75c435d76696a51942 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Dec 2024 12:01:22 +0900 Subject: [PATCH 188/273] refactor(goal_planner): move unnecessary member functions (#9522) Signed-off-by: Mamoru Sobue --- .../goal_planner_module.hpp | 86 ++++--- .../src/goal_planner_module.cpp | 209 ++++++++---------- 2 files changed, 126 insertions(+), 169 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 5d7fe103a9346..914da46e60180 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -135,6 +135,43 @@ struct PullOverContextData std::optional last_path_idx_increment_time; }; +bool isOnModifiedGoal( + const Pose & current_pose, const std::optional & modified_goal_opt, + const GoalPlannerParameters & parameters); + +bool hasPreviousModulePathShapeChanged( + const BehaviorModuleOutput & previous_module_output, + const BehaviorModuleOutput & last_previous_module_output); +bool hasDeviatedFromLastPreviousModulePath( + const PlannerData & planner_data, const BehaviorModuleOutput & last_previous_module_output); +bool hasDeviatedFromCurrentPreviousModulePath( + const PlannerData & planner_data, const BehaviorModuleOutput & previous_module_output); + +bool needPathUpdate( + const Pose & current_pose, const double path_update_duration, const rclcpp::Time & now, + const std::optional & modified_goal, + const std::optional & selected_time, const GoalPlannerParameters & parameters); + +bool checkOccupancyGridCollision( + const PathWithLaneId & path, + const std::shared_ptr occupancy_grid_map); + +bool isStopped( + std::deque & odometry_buffer, + const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower); + +// Flag class for managing whether a certain callback is running in multi-threading +class ScopedFlag +{ +public: + explicit ScopedFlag(std::atomic & flag) : flag_(flag) { flag_.store(true); } + + ~ScopedFlag() { flag_.store(false); } + +private: + std::atomic & flag_; +}; + class GoalPlannerModule : public SceneModuleInterface { public: @@ -193,18 +230,6 @@ class GoalPlannerModule : public SceneModuleInterface void processOnExit() override; void updateData() override; - void updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & goal_planner_params); - - void updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & goal_planner_params); - - void updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & goal_planner_params); - void postProcess() override; void setParameters(const std::shared_ptr & parameters); void acceptVisitor( @@ -257,18 +282,6 @@ class GoalPlannerModule : public SceneModuleInterface std::optional gp_planner_data_{std::nullopt}; std::mutex gp_planner_data_mutex_; - // Flag class for managing whether a certain callback is running in multi-threading - class ScopedFlag - { - public: - explicit ScopedFlag(std::atomic & flag) : flag_(flag) { flag_.store(true); } - - ~ScopedFlag() { flag_.store(false); } - - private: - std::atomic & flag_; - }; - /* * state transitions and plan function used in each state * @@ -359,11 +372,6 @@ class GoalPlannerModule : public SceneModuleInterface mutable GoalPlannerDebugData debug_data_; mutable PoseWithString debug_stop_pose_with_info_; - // collision check - bool checkOccupancyGridCollision( - const PathWithLaneId & path, - const std::shared_ptr occupancy_grid_map) const; - // goal seach GoalCandidates generateGoalCandidates() const; @@ -380,18 +388,8 @@ class GoalPlannerModule : public SceneModuleInterface double calcSignedArcLengthFromEgo(const PathWithLaneId & path, const Pose & pose) const; // status - bool isStopped(); - bool isStopped( - std::deque & odometry_buffer, const double time); bool hasFinishedCurrentPath(const PullOverContextData & ctx_data); - bool isOnModifiedGoal( - const Pose & current_pose, const std::optional & modified_goal_opt, - const GoalPlannerParameters & parameters) const; double calcModuleRequestLength() const; - bool needPathUpdate( - const Pose & current_pose, const double path_update_duration, - const std::optional & modified_goal_opt, - const GoalPlannerParameters & parameters) const; bool isStuck( const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, const std::shared_ptr planner_data, @@ -443,16 +441,6 @@ class GoalPlannerModule : public SceneModuleInterface TurnSignalInfo calcTurnSignalInfo(const PullOverContextData & context_data); std::optional ignore_signal_{std::nullopt}; - bool hasPreviousModulePathShapeChanged( - const BehaviorModuleOutput & previous_module_output, - const BehaviorModuleOutput & last_previous_module_output) const; - bool hasDeviatedFromLastPreviousModulePath( - const std::shared_ptr planner_data, - const BehaviorModuleOutput & last_previous_module_output) const; - bool hasDeviatedFromCurrentPreviousModulePath( - const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) const; - // timer for generating pull over path candidates in a separate thread void onTimer(); void onFreespaceParkingTimer(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index fed42be0753d7..d8bf8f42386db 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -53,7 +53,6 @@ using autoware::motion_utils::insertDecelPoint; using autoware::universe_utils::calcDistance2d; using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::createMarkerColor; -using autoware::universe_utils::inverseTransformPose; using nav_msgs::msg::OccupancyGrid; namespace autoware::behavior_path_planner @@ -145,9 +144,27 @@ GoalPlannerModule::GoalPlannerModule( // time_keeper_->add_reporter(&std::cerr); } -bool GoalPlannerModule::hasPreviousModulePathShapeChanged( +bool isOnModifiedGoal( + const Pose & current_pose, const GoalCandidate & modified_goal, + const GoalPlannerParameters & parameters) +{ + return calcDistance2d(current_pose, modified_goal.goal_pose) < parameters.th_arrived_distance; +} + +bool isOnModifiedGoal( + const Pose & current_pose, const std::optional & modified_goal_opt, + const GoalPlannerParameters & parameters) +{ + if (!modified_goal_opt) { + return false; + } + + return isOnModifiedGoal(current_pose, modified_goal_opt.value(), parameters); +} + +bool hasPreviousModulePathShapeChanged( const BehaviorModuleOutput & previous_module_output, - const BehaviorModuleOutput & last_previous_module_output) const + const BehaviorModuleOutput & last_previous_module_output) { // Calculate the lateral distance between each point of the current path and the nearest point of // the last path @@ -180,25 +197,69 @@ bool GoalPlannerModule::hasPreviousModulePathShapeChanged( return false; } -bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath( - const std::shared_ptr planner_data, - const BehaviorModuleOutput & last_previous_module_output) const +bool hasDeviatedFromLastPreviousModulePath( + const PlannerData & planner_data, const BehaviorModuleOutput & last_previous_module_output) { return std::abs(autoware::motion_utils::calcLateralOffset( last_previous_module_output.path.points, - planner_data->self_odometry->pose.pose.position)) > 0.3; + planner_data.self_odometry->pose.pose.position)) > 0.3; } -bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath( - const std::shared_ptr planner_data, - const BehaviorModuleOutput & previous_module_output) const +bool hasDeviatedFromCurrentPreviousModulePath( + const PlannerData & planner_data, const BehaviorModuleOutput & previous_module_output) { constexpr double LATERAL_DEVIATION_THRESH = 0.3; return std::abs(autoware::motion_utils::calcLateralOffset( - previous_module_output.path.points, planner_data->self_odometry->pose.pose.position)) > + previous_module_output.path.points, planner_data.self_odometry->pose.pose.position)) > LATERAL_DEVIATION_THRESH; } +bool needPathUpdate( + const Pose & current_pose, const double path_update_duration, const rclcpp::Time & now, + const std::optional & modified_goal, + const std::optional & selected_time, const GoalPlannerParameters & parameters) +{ + const bool has_enough_time_passed = + selected_time ? (now - selected_time.value()).seconds() > path_update_duration : true; + return !isOnModifiedGoal(current_pose, modified_goal, parameters) && has_enough_time_passed; +} + +bool checkOccupancyGridCollision( + const PathWithLaneId & path, + const std::shared_ptr occupancy_grid_map) +{ + if (!occupancy_grid_map) { + return false; + } + const bool check_out_of_range = false; + return occupancy_grid_map->hasObstacleOnPath(path, check_out_of_range); +} + +bool isStopped( + std::deque & odometry_buffer, + const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower) +{ + odometry_buffer.push_back(self_odometry); + // Delete old data in buffer_stuck_ + while (rclcpp::ok()) { + const auto time_diff = rclcpp::Time(odometry_buffer.back()->header.stamp) - + rclcpp::Time(odometry_buffer.front()->header.stamp); + if (time_diff.seconds() < duration_lower) { + break; + } + odometry_buffer.pop_front(); + } + bool is_stopped = true; + for (const auto & odometry : odometry_buffer) { + const double ego_vel = utils::l2Norm(odometry->twist.twist.linear); + if (ego_vel > duration_lower) { + is_stopped = false; + break; + } + } + return is_stopped; +} + // generate pull over candidate paths void GoalPlannerModule::onTimer() { @@ -273,7 +334,7 @@ void GoalPlannerModule::onTimer() local_planner_data->self_odometry->pose.pose, modified_goal_opt, parameters)) { return false; } - if (hasDeviatedFromCurrentPreviousModulePath(local_planner_data, previous_module_output)) { + if (hasDeviatedFromCurrentPreviousModulePath(*local_planner_data, previous_module_output)) { RCLCPP_DEBUG(getLogger(), "has deviated from current previous module path"); return false; } @@ -285,7 +346,7 @@ void GoalPlannerModule::onTimer() return true; } if ( - hasDeviatedFromLastPreviousModulePath(local_planner_data, last_previous_module_output) && + hasDeviatedFromLastPreviousModulePath(*local_planner_data, last_previous_module_output) && current_state != PathDecisionState::DecisionKind::DECIDED) { RCLCPP_DEBUG(getLogger(), "has deviated from last previous module path"); return true; @@ -464,8 +525,8 @@ void GoalPlannerModule::onFreespaceParkingTimer() parameters) && is_new_costmap && needPathUpdate( - local_planner_data->self_odometry->pose.pose, path_update_duration, modified_goal_opt, - parameters)) { + local_planner_data->self_odometry->pose.pose, path_update_duration, clock_->now(), + modified_goal_opt, thread_safe_data_.get_last_path_update_time(), parameters)) { auto goal_searcher = std::make_shared(parameters, vehicle_footprint); planFreespacePath( @@ -474,30 +535,6 @@ void GoalPlannerModule::onFreespaceParkingTimer() } } -void GoalPlannerModule::updateEgoPredictedPathParams( - std::shared_ptr & ego_predicted_path_params, - const std::shared_ptr & goal_planner_params) -{ - ego_predicted_path_params = - std::make_shared(goal_planner_params->ego_predicted_path_params); -} - -void GoalPlannerModule::updateSafetyCheckParams( - std::shared_ptr & safety_check_params, - const std::shared_ptr & goal_planner_params) -{ - safety_check_params = - std::make_shared(goal_planner_params->safety_check_params); -} - -void GoalPlannerModule::updateObjectsFilteringParams( - std::shared_ptr & objects_filtering_params, - const std::shared_ptr & goal_planner_params) -{ - objects_filtering_params = - std::make_shared(goal_planner_params->objects_filtering_params); -} - void GoalPlannerModule::updateData() { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -640,9 +677,11 @@ void GoalPlannerModule::updateData() void GoalPlannerModule::initializeSafetyCheckParameters() { - updateEgoPredictedPathParams(ego_predicted_path_params_, parameters_); - updateSafetyCheckParams(safety_check_params_, parameters_); - updateObjectsFilteringParams(objects_filtering_params_, parameters_); + ego_predicted_path_params_ = + std::make_shared(parameters_->ego_predicted_path_params); + safety_check_params_ = std::make_shared(parameters_->safety_check_params); + objects_filtering_params_ = + std::make_shared(parameters_->objects_filtering_params); } void GoalPlannerModule::processOnExit() @@ -830,7 +869,8 @@ bool GoalPlannerModule::planFreespacePath( bool GoalPlannerModule::canReturnToLaneParking(const PullOverContextData & context_data) { // return only before starting free space parking - if (!isStopped()) { + if (!isStopped( + odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time)) { return false; } @@ -1384,8 +1424,8 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput( PathDecisionState::DecisionKind::NOT_DECIDED && !is_freespace && needPathUpdate( - planner_data_->self_odometry->pose.pose, 1.0 /*path_update_duration*/, modified_goal_opt, - *parameters_)) { + planner_data_->self_odometry->pose.pose, 1.0 /*path_update_duration*/, clock_->now(), + modified_goal_opt, thread_safe_data_.get_last_path_update_time(), *parameters_)) { // if the final path is not decided and enough time has passed since last path update, // select safe path from lane parking pull over path candidates // and set it to thread_safe_data_ @@ -1686,37 +1726,6 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath(const PathWithLaneId return stop_path; } -bool GoalPlannerModule::isStopped( - std::deque & odometry_buffer, const double time) -{ - const std::lock_guard lock(mutex_); - odometry_buffer.push_back(planner_data_->self_odometry); - // Delete old data in buffer - while (rclcpp::ok()) { - const auto time_diff = rclcpp::Time(odometry_buffer.back()->header.stamp) - - rclcpp::Time(odometry_buffer.front()->header.stamp); - if (time_diff.seconds() < time) { - break; - } - odometry_buffer.pop_front(); - } - bool is_stopped = true; - for (const auto & odometry : odometry_buffer) { - const double ego_vel = utils::l2Norm(odometry->twist.twist.linear); - if (ego_vel > parameters_->th_stopped_velocity) { - is_stopped = false; - break; - } - } - return is_stopped; -} - -bool GoalPlannerModule::isStopped() -{ - const std::lock_guard lock(mutex_); - return isStopped(odometry_buffer_stopped_, parameters_->th_stopped_time); -} - bool GoalPlannerModule::isStuck( const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, const std::shared_ptr planner_data, @@ -1737,7 +1746,7 @@ bool GoalPlannerModule::isStuck( } constexpr double stuck_time = 5.0; - if (!isStopped(odometry_buffer_stuck_, stuck_time)) { + if (!isStopped(odometry_buffer_stuck_, planner_data->self_odometry, stuck_time)) { return false; } @@ -1777,7 +1786,8 @@ bool GoalPlannerModule::hasFinishedCurrentPath(const PullOverContextData & ctx_d return false; } - if (!isStopped()) { + if (!isStopped( + odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time)) { return false; } @@ -1813,18 +1823,6 @@ bool GoalPlannerModule::hasFinishedCurrentPath(const PullOverContextData & ctx_d parameters_->th_arrived_distance; } -bool GoalPlannerModule::isOnModifiedGoal( - const Pose & current_pose, const std::optional & modified_goal_opt, - const GoalPlannerParameters & parameters) const -{ - if (!modified_goal_opt) { - return false; - } - - return calcDistance2d(current_pose, modified_goal_opt.value().goal_pose) < - parameters.th_arrived_distance; -} - TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo(const PullOverContextData & context_data) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1902,17 +1900,6 @@ TurnSignalInfo GoalPlannerModule::calcTurnSignalInfo(const PullOverContextData & return new_signal; } -bool GoalPlannerModule::checkOccupancyGridCollision( - const PathWithLaneId & path, - const std::shared_ptr occupancy_grid_map) const -{ - if (!occupancy_grid_map) { - return false; - } - const bool check_out_of_range = false; - return occupancy_grid_map->hasObstacleOnPath(path, check_out_of_range); -} - bool GoalPlannerModule::hasEnoughDistance( const PullOverPath & pull_over_path, const PathWithLaneId & long_tail_reference_path) const { @@ -2544,10 +2531,10 @@ void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) occupancy_grid_map_, *parameters_)) { marker.text += " stuck"; } - */ if (isStopped()) { marker.text += " stopped"; } + */ if (debug_data_.freespace_planner.is_planning) { marker.text += @@ -2574,24 +2561,6 @@ void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) } } -bool GoalPlannerModule::needPathUpdate( - const Pose & current_pose, const double path_update_duration, - const std::optional & modified_goal_opt, - const GoalPlannerParameters & parameters) const -{ - return !isOnModifiedGoal(current_pose, modified_goal_opt, parameters) && - hasEnoughTimePassedSincePathUpdate(path_update_duration); -} - -bool GoalPlannerModule::hasEnoughTimePassedSincePathUpdate(const double duration) const -{ - if (!thread_safe_data_.get_last_path_update_time()) { - return true; - } - - return (clock_->now() - *thread_safe_data_.get_last_path_update_time()).seconds() > duration; -} - void GoalPlannerModule::GoalPlannerData::initializeOccupancyGridMap( const PlannerData & planner_data, const GoalPlannerParameters & parameters) { From a77f4880c70d3d03ca03951c75a3f9cefa26aeb4 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 2 Dec 2024 12:30:28 +0900 Subject: [PATCH 189/273] fix(learning_based_vehicle_model): fix clang-diagnostic-delete-abstract-non-virtual-dtor (#9446) Signed-off-by: veqcc --- .../include/learning_based_vehicle_model/submodel_interface.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp b/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp index d4662036709d5..1cbad103278fb 100644 --- a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp +++ b/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp @@ -20,6 +20,8 @@ class SubModelInterface { public: + virtual ~SubModelInterface() = default; + /** * @brief set time step of the model * @param [in] dt time step From 557a8b57f76d03acacb5c979f2c171a1a03cac28 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Dec 2024 12:35:32 +0900 Subject: [PATCH 190/273] refactor(goal_planner): move PathDecisionController implementation to a different file (#9523) refactor(goal_planner): move decision_state implementation Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 1 + .../src/decision_state.cpp | 187 ++++++++++++++++++ .../src/goal_planner_module.cpp | 163 --------------- 3 files changed, 188 insertions(+), 163 deletions(-) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt index d3f7f7a4015f0..8e945093659c1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CMakeLists.txt @@ -19,6 +19,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/util.cpp src/goal_planner_module.cpp src/manager.cpp + src/decision_state.cpp ) if(BUILD_EXAMPLES) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp new file mode 100644 index 0000000000000..827e1269cfa80 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp @@ -0,0 +1,187 @@ +// 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/behavior_path_goal_planner_module/util.hpp" + +#include +#include + +namespace autoware::behavior_path_planner +{ + +using autoware::motion_utils::calcSignedArcLength; + +void PathDecisionStateController::transit_state( + const bool found_pull_over_path, const rclcpp::Time & now, + const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, + const std::optional modified_goal_opt, + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const bool is_current_safe, const GoalPlannerParameters & parameters, + const std::shared_ptr goal_searcher, const bool is_activated, + const std::optional & pull_over_path, + std::vector & ego_polygons_expanded) +{ + const auto next_state = get_next_state( + found_pull_over_path, now, static_target_objects, dynamic_target_objects, modified_goal_opt, + planner_data, occupancy_grid_map, is_current_safe, parameters, goal_searcher, is_activated, + pull_over_path, ego_polygons_expanded); + current_state_ = next_state; +} + +PathDecisionState PathDecisionStateController::get_next_state( + const bool found_pull_over_path, const rclcpp::Time & now, + const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, + const std::optional modified_goal_opt, + const std::shared_ptr planner_data, + const std::shared_ptr occupancy_grid_map, + const bool is_current_safe, const GoalPlannerParameters & parameters, + const std::shared_ptr goal_searcher, const bool is_activated, + const std::optional & pull_over_path_opt, + std::vector & ego_polygons_expanded) const +{ + auto next_state = current_state_; + + // update safety + if (!parameters.safety_check_params.enable_safety_check) { + next_state.is_stable_safe = true; + } else { + if (is_current_safe) { + if (!next_state.safe_start_time) { + next_state.safe_start_time = now; + next_state.is_stable_safe = false; + } else { + next_state.is_stable_safe = + ((now - next_state.safe_start_time.value()).seconds() > + parameters.safety_check_params.keep_unsafe_time); + } + } else { + next_state.safe_start_time = std::nullopt; + next_state.is_stable_safe = false; + } + } + + // Once this function returns true, it will continue to return true thereafter + if (next_state.state == PathDecisionState::DecisionKind::DECIDED) { + return next_state; + } + + // if path is not safe, not decided + if (!found_pull_over_path || !pull_over_path_opt) { + next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; + return next_state; + } + + const auto & pull_over_path = pull_over_path_opt.value(); + const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; + // If it is dangerous against dynamic objects before approval, do not determine the path. + // This eliminates a unsafe path to be approved + if (enable_safety_check && !next_state.is_stable_safe && !is_activated) { + RCLCPP_DEBUG( + logger_, + "[DecidingPathStatus]: NOT_DECIDED. path is not safe against dynamic objects before " + "approval"); + next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; + return next_state; + } + + const auto & current_path = pull_over_path.getCurrentPath(); + if (current_state_.state == PathDecisionState::DecisionKind::DECIDING) { + const double hysteresis_factor = 0.9; + + // check goal pose collision + if ( + modified_goal_opt && !goal_searcher->isSafeGoalWithMarginScaleFactor( + modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, + planner_data, static_target_objects)) { + RCLCPP_DEBUG(logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe"); + next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; + next_state.deciding_start_time = std::nullopt; + return next_state; + } + + // check current parking path collision + const auto & parking_path = pull_over_path.parking_path(); + const auto & parking_path_curvatures = pull_over_path.parking_path_curvatures(); + const double margin = + parameters.object_recognition_collision_check_hard_margins.back() * hysteresis_factor; + if (goal_planner_utils::checkObjectsCollision( + parking_path, parking_path_curvatures, static_target_objects, dynamic_target_objects, + planner_data->parameters, margin, + /*extract_static_objects=*/false, parameters.maximum_deceleration, + parameters.object_recognition_collision_check_max_extra_stopping_margin, + ego_polygons_expanded, true)) { + RCLCPP_DEBUG( + logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path has collision with objects"); + next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; + next_state.deciding_start_time = std::nullopt; + return next_state; + } + + if (enable_safety_check && !next_state.is_stable_safe) { + RCLCPP_DEBUG( + logger_, + "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path is not safe against dynamic objects"); + next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; + return next_state; + } + + // if enough time has passed since deciding status starts, transition to DECIDED + constexpr double check_collision_duration = 1.0; + const double elapsed_time_from_deciding = + (now - current_state_.deciding_start_time.value()).seconds(); + if (elapsed_time_from_deciding > check_collision_duration) { + RCLCPP_DEBUG(logger_, "[DecidingPathStatus]: DECIDING->DECIDED. has enough safe time passed"); + next_state.state = PathDecisionState::DecisionKind::DECIDED; + next_state.deciding_start_time = std::nullopt; + return next_state; + } + + // if enough time has NOT passed since deciding status starts, keep DECIDING + RCLCPP_DEBUG( + logger_, "[DecidingPathStatus]: keep DECIDING. elapsed_time_from_deciding: %f", + elapsed_time_from_deciding); + return next_state; + } + + // if ego is sufficiently close to the start of the nearest candidate path, the path is decided + const auto & current_pose = planner_data->self_odometry->pose.pose; + const size_t ego_segment_idx = + autoware::motion_utils::findNearestSegmentIndex(current_path.points, current_pose.position); + + const size_t start_pose_segment_idx = autoware::motion_utils::findNearestSegmentIndex( + current_path.points, pull_over_path.start_pose().position); + const double dist_to_parking_start_pose = calcSignedArcLength( + current_path.points, current_pose.position, ego_segment_idx, + pull_over_path.start_pose().position, start_pose_segment_idx); + if (dist_to_parking_start_pose > parameters.decide_path_distance) { + next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; + return next_state; + } + + // if object recognition for path collision check is enabled, transition to DECIDING to check + // collision for a certain period of time. Otherwise, transition to DECIDED directly. + if (parameters.use_object_recognition) { + RCLCPP_DEBUG( + logger_, + "[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain " + "period of time"); + next_state.state = PathDecisionState::DecisionKind::DECIDING; + next_state.deciding_start_time = now; + return next_state; + } + return {PathDecisionState::DecisionKind::DECIDED, std::nullopt}; +} + +} // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index d8bf8f42386db..6b216e83833c4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -28,7 +28,6 @@ #include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" #include #include @@ -2605,166 +2604,4 @@ void GoalPlannerModule::GoalPlannerData::update( goal_candidates = goal_candidates_; } -void PathDecisionStateController::transit_state( - const bool found_pull_over_path, const rclcpp::Time & now, - const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, - const std::optional modified_goal_opt, - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const bool is_current_safe, const GoalPlannerParameters & parameters, - const std::shared_ptr goal_searcher, const bool is_activated, - const std::optional & pull_over_path, - std::vector & ego_polygons_expanded) -{ - const auto next_state = get_next_state( - found_pull_over_path, now, static_target_objects, dynamic_target_objects, modified_goal_opt, - planner_data, occupancy_grid_map, is_current_safe, parameters, goal_searcher, is_activated, - pull_over_path, ego_polygons_expanded); - current_state_ = next_state; -} - -PathDecisionState PathDecisionStateController::get_next_state( - const bool found_pull_over_path, const rclcpp::Time & now, - const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, - const std::optional modified_goal_opt, - const std::shared_ptr planner_data, - const std::shared_ptr occupancy_grid_map, - const bool is_current_safe, const GoalPlannerParameters & parameters, - const std::shared_ptr goal_searcher, const bool is_activated, - const std::optional & pull_over_path_opt, - std::vector & ego_polygons_expanded) const -{ - auto next_state = current_state_; - - // update safety - if (!parameters.safety_check_params.enable_safety_check) { - next_state.is_stable_safe = true; - } else { - if (is_current_safe) { - if (!next_state.safe_start_time) { - next_state.safe_start_time = now; - next_state.is_stable_safe = false; - } else { - next_state.is_stable_safe = - ((now - next_state.safe_start_time.value()).seconds() > - parameters.safety_check_params.keep_unsafe_time); - } - } else { - next_state.safe_start_time = std::nullopt; - next_state.is_stable_safe = false; - } - } - - // Once this function returns true, it will continue to return true thereafter - if (next_state.state == PathDecisionState::DecisionKind::DECIDED) { - return next_state; - } - - // if path is not safe, not decided - if (!found_pull_over_path || !pull_over_path_opt) { - next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; - return next_state; - } - - const auto & pull_over_path = pull_over_path_opt.value(); - const bool enable_safety_check = parameters.safety_check_params.enable_safety_check; - // If it is dangerous against dynamic objects before approval, do not determine the path. - // This eliminates a unsafe path to be approved - if (enable_safety_check && !next_state.is_stable_safe && !is_activated) { - RCLCPP_DEBUG( - logger_, - "[DecidingPathStatus]: NOT_DECIDED. path is not safe against dynamic objects before " - "approval"); - next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; - return next_state; - } - - const auto & current_path = pull_over_path.getCurrentPath(); - if (current_state_.state == PathDecisionState::DecisionKind::DECIDING) { - const double hysteresis_factor = 0.9; - - // check goal pose collision - if ( - modified_goal_opt && !goal_searcher->isSafeGoalWithMarginScaleFactor( - modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map, - planner_data, static_target_objects)) { - RCLCPP_DEBUG(logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe"); - next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; - next_state.deciding_start_time = std::nullopt; - return next_state; - } - - // check current parking path collision - const auto & parking_path = pull_over_path.parking_path(); - const auto & parking_path_curvatures = pull_over_path.parking_path_curvatures(); - const double margin = - parameters.object_recognition_collision_check_hard_margins.back() * hysteresis_factor; - if (goal_planner_utils::checkObjectsCollision( - parking_path, parking_path_curvatures, static_target_objects, dynamic_target_objects, - planner_data->parameters, margin, - /*extract_static_objects=*/false, parameters.maximum_deceleration, - parameters.object_recognition_collision_check_max_extra_stopping_margin, - ego_polygons_expanded, true)) { - RCLCPP_DEBUG( - logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path has collision with objects"); - next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; - next_state.deciding_start_time = std::nullopt; - return next_state; - } - - if (enable_safety_check && !next_state.is_stable_safe) { - RCLCPP_DEBUG( - logger_, - "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path is not safe against dynamic objects"); - next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; - return next_state; - } - - // if enough time has passed since deciding status starts, transition to DECIDED - constexpr double check_collision_duration = 1.0; - const double elapsed_time_from_deciding = - (now - current_state_.deciding_start_time.value()).seconds(); - if (elapsed_time_from_deciding > check_collision_duration) { - RCLCPP_DEBUG(logger_, "[DecidingPathStatus]: DECIDING->DECIDED. has enough safe time passed"); - next_state.state = PathDecisionState::DecisionKind::DECIDED; - next_state.deciding_start_time = std::nullopt; - return next_state; - } - - // if enough time has NOT passed since deciding status starts, keep DECIDING - RCLCPP_DEBUG( - logger_, "[DecidingPathStatus]: keep DECIDING. elapsed_time_from_deciding: %f", - elapsed_time_from_deciding); - return next_state; - } - - // if ego is sufficiently close to the start of the nearest candidate path, the path is decided - const auto & current_pose = planner_data->self_odometry->pose.pose; - const size_t ego_segment_idx = - autoware::motion_utils::findNearestSegmentIndex(current_path.points, current_pose.position); - - const size_t start_pose_segment_idx = autoware::motion_utils::findNearestSegmentIndex( - current_path.points, pull_over_path.start_pose().position); - const double dist_to_parking_start_pose = calcSignedArcLength( - current_path.points, current_pose.position, ego_segment_idx, - pull_over_path.start_pose().position, start_pose_segment_idx); - if (dist_to_parking_start_pose > parameters.decide_path_distance) { - next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED; - return next_state; - } - - // if object recognition for path collision check is enabled, transition to DECIDING to check - // collision for a certain period of time. Otherwise, transition to DECIDED directly. - if (parameters.use_object_recognition) { - RCLCPP_DEBUG( - logger_, - "[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain " - "period of time"); - next_state.state = PathDecisionState::DecisionKind::DECIDING; - next_state.deciding_start_time = now; - return next_state; - } - return {PathDecisionState::DecisionKind::DECIDED, std::nullopt}; -} - } // namespace autoware::behavior_path_planner From 2a34c953e624ba001da08d8d4e592cd5c70b2115 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 2 Dec 2024 07:39:59 +0300 Subject: [PATCH 191/273] ci(sync-files): make use of sync-files-templates repo (#9527) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/sync-files.yaml | 51 ++++++++++++++++++----------------------- 1 file changed, 22 insertions(+), 29 deletions(-) diff --git a/.github/sync-files.yaml b/.github/sync-files.yaml index e70d3daf88509..4c09e072766fa 100644 --- a/.github/sync-files.yaml +++ b/.github/sync-files.yaml @@ -1,55 +1,48 @@ -- repository: autowarefoundation/autoware +- repository: autowarefoundation/sync-file-templates + source-dir: sources files: - - source: CODE_OF_CONDUCT.md - - source: CONTRIBUTING.md - - source: DISCLAIMER.md - - source: LICENSE - source: .github/ISSUE_TEMPLATE/bug.yaml - source: .github/ISSUE_TEMPLATE/config.yml - source: .github/ISSUE_TEMPLATE/task.yaml - source: .github/dependabot.yaml + - source: .github/pull_request_template_complex.md + dest: .github/pull_request_template.md - source: .github/stale.yml - source: .github/workflows/cancel-previous-workflows.yaml + - source: .github/workflows/check-build-depends.yaml + - source: .github/workflows/clang-tidy-pr-comments.yaml + - source: .github/workflows/clang-tidy-pr-comments-manually.yaml + - source: .github/workflows/comment-on-pr.yaml + - source: .github/workflows/delete-closed-pr-docs.yaml + - source: .github/workflows/deploy-docs.yaml - source: .github/workflows/github-release.yaml - source: .github/workflows/pre-commit.yaml - source: .github/workflows/pre-commit-optional.yaml + - source: .github/workflows/pre-commit-optional-autoupdate.yaml + - source: .github/workflows/pre-commit-autoupdate.yaml - source: .github/workflows/semantic-pull-request.yaml - source: .github/workflows/spell-check-differential.yaml pre-commands: | sd " with:\n" " with:\n local-cspell-json: .cspell.json\n" {source} - - source: .github/workflows/spell-check-differential.yaml - dest: .github/workflows/spell-check-daily.yaml + - source: .github/workflows/spell-check-daily.yaml pre-commands: | - sd "spell-check-differential" "spell-check-daily" {source} - sd " with:\n" " with:\n local-cspell-json: .cspell.json\n incremental-files-only: false\n" {source} - sd "on:\n pull_request:\n" "on:\n schedule:\n - cron: 0 0 * * *\n workflow_dispatch:\n" {source} + sd " with:\n" " with:\n local-cspell-json: .cspell.json\n" {source} - source: .github/workflows/sync-files.yaml + - source: .github/workflows/update-codeowners-from-packages.yaml + - source: docs/assets/js/mathjax.js - source: .clang-format - source: .markdown-link-check.json - source: .markdownlint.yaml - source: .pre-commit-config-optional.yaml + - source: .pre-commit-config.yaml - source: .prettierignore - source: .prettierrc.yaml - source: .yamllint.yaml + - source: CODE_OF_CONDUCT.md + - source: CONTRIBUTING.md - source: CPPLINT.cfg - - source: setup.cfg - -- repository: autowarefoundation/autoware_common - files: - - source: .github/workflows/clang-tidy-differential.yaml - pre-commands: | - sd 'container: ros:(\w+)' 'container: ghcr.io/autowarefoundation/autoware:universe-devel-cuda' {source} - - source: .github/workflows/check-build-depends.yaml - - source: .github/workflows/clang-tidy-pr-comments.yaml - - source: .github/workflows/clang-tidy-pr-comments-manually.yaml - - source: .github/workflows/update-codeowners-from-packages.yaml - - source: .pre-commit-config.yaml - - source: codecov.yaml - -- repository: autowarefoundation/autoware-documentation - files: - - source: .github/workflows/deploy-docs.yaml - - source: .github/workflows/delete-closed-pr-docs.yaml + - source: DISCLAIMER.md + - source: LICENSE - source: mkdocs-base.yaml dest: mkdocs.yaml pre-commands: | @@ -63,4 +56,4 @@ " - macros" \ " - macros: module_name: mkdocs_macros" {source} - - source: docs/assets/js/mathjax.js + - source: setup.cfg From 41c5956518cea2a02c4393c13a7efcea50bc5a19 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Mon, 2 Dec 2024 08:08:19 +0300 Subject: [PATCH 192/273] refactor: correct spelling (#9528) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .cspell.json | 2 +- .../include/autoware/trajectory/point.hpp | 6 +++--- .../test/test_trajectory_container.cpp | 6 +++--- .../config/plot_juggler_trajectory_follower.xml | 6 +++--- .../lib/tensorrt_shape_estimator.cpp | 4 ++-- .../src/costmap_generator.cpp | 4 ++-- .../test/src/test_freespace_planning_algorithms.cpp | 12 ++++++------ planning/autoware_path_smoother/src/elastic_band.cpp | 6 +++--- .../src/scene_intersection_prepare_data.cpp | 2 +- .../test/test_util.cpp | 2 +- .../autoware_sampler_common/test/test_transform.cpp | 6 +++--- simulator/autoware_carla_interface/README.md | 6 +++--- 12 files changed, 31 insertions(+), 31 deletions(-) diff --git a/.cspell.json b/.cspell.json index 2d024a5ca589d..f338e72d194e3 100644 --- a/.cspell.json +++ b/.cspell.json @@ -4,5 +4,5 @@ "planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/scripts/**" ], "ignoreRegExpList": [], - "words": ["dltype", "tvmgen", "fromarray", "soblin"] + "words": ["dltype", "tvmgen", "fromarray", "soblin", "brkay54"] } diff --git a/common/autoware_trajectory/include/autoware/trajectory/point.hpp b/common/autoware_trajectory/include/autoware/trajectory/point.hpp index e9d985a85194a..3e763e2428f1b 100644 --- a/common/autoware_trajectory/include/autoware/trajectory/point.hpp +++ b/common/autoware_trajectory/include/autoware/trajectory/point.hpp @@ -122,7 +122,7 @@ class Trajectory using trajectory::detail::to_point; Eigen::Vector2d point(to_point(p).x, to_point(p).y); std::vector distances_from_segments; - std::vector lengthes_from_start_points; + std::vector lengths_from_start_points; auto axis = detail::crop_bases(bases_, start_, end_); @@ -149,7 +149,7 @@ class Trajectory } if (constraints(length_from_start_point)) { distances_from_segments.push_back(distance_from_segment); - lengthes_from_start_points.push_back(length_from_start_point); + lengths_from_start_points.push_back(length_from_start_point); } } if (distances_from_segments.empty()) { @@ -158,7 +158,7 @@ class Trajectory auto min_it = std::min_element(distances_from_segments.begin(), distances_from_segments.end()); - return lengthes_from_start_points[std::distance(distances_from_segments.begin(), min_it)] - + return lengths_from_start_points[std::distance(distances_from_segments.begin(), min_it)] - start_; } diff --git a/common/autoware_trajectory/test/test_trajectory_container.cpp b/common/autoware_trajectory/test/test_trajectory_container.cpp index b3e4c16a09999..028d36d98a954 100644 --- a/common/autoware_trajectory/test/test_trajectory_container.cpp +++ b/common/autoware_trajectory/test/test_trajectory_container.cpp @@ -106,9 +106,9 @@ TEST_F(TrajectoryTest, direction) TEST_F(TrajectoryTest, curvature) { - double curv = trajectory->curvature(0.0); - EXPECT_LT(-1.0, curv); - EXPECT_LT(curv, 1.0); + double curvature_val = trajectory->curvature(0.0); + EXPECT_LT(-1.0, curvature_val); + EXPECT_LT(curvature_val, 1.0); } TEST_F(TrajectoryTest, restore) diff --git a/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml b/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml index e458edaf6c471..0de08076b8c06 100644 --- a/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml +++ b/control/autoware_trajectory_follower_node/config/plot_juggler_trajectory_follower.xml @@ -258,7 +258,7 @@ - + @@ -268,7 +268,7 @@ - + @@ -286,7 +286,7 @@ - + diff --git a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp index 072d3b661b8b3..4cb8c0083a148 100644 --- a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp +++ b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp @@ -140,7 +140,7 @@ void TrtShapeEstimator::preprocess(const DetectedObjectsWithFeature & input) } int iter_count = static_cast(input_pc_size) / point_size_of_cloud; - int remainer_count = static_cast(input_pc_size) % point_size_of_cloud; + int remaining_points_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++) { @@ -155,7 +155,7 @@ void TrtShapeEstimator::preprocess(const DetectedObjectsWithFeature & input) } } - for (int j = 0; j < remainer_count; j++) { + for (int j = 0; j < remaining_points_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]; diff --git a/planning/autoware_costmap_generator/src/costmap_generator.cpp b/planning/autoware_costmap_generator/src/costmap_generator.cpp index d791836fa0a08..4092acae9b51c 100644 --- a/planning/autoware_costmap_generator/src/costmap_generator.cpp +++ b/planning/autoware_costmap_generator/src/costmap_generator.cpp @@ -324,8 +324,8 @@ bool CostmapGenerator::isActive() if (param_->activate_by_scenario) { if (!scenario_) return false; const auto & s = scenario_->activating_scenarios; - return std::any_of(s.begin(), s.end(), [](const auto scen) { - return scen == tier4_planning_msgs::msg::Scenario::PARKING; + return std::any_of(s.begin(), s.end(), [](const auto scenario) { + return scenario == tier4_planning_msgs::msg::Scenario::PARKING; }); } diff --git a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp index a2ed4c3e7e0fc..a46b8bba58920 100644 --- a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp +++ b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp @@ -231,9 +231,9 @@ std::unique_ptr configure_astar(bool use_multi) obstacle_distance_weight, goal_lat_distance_weight}; - auto clock_shrd_ptr = std::make_shared(RCL_ROS_TIME); - auto algo = std::make_unique( - planner_common_param, vehicle_shape, astar_param, clock_shrd_ptr); + auto clock_ptr = std::make_shared(RCL_ROS_TIME); + auto algo = + std::make_unique(planner_common_param, vehicle_shape, astar_param, clock_ptr); return algo; } @@ -247,9 +247,9 @@ std::unique_ptr configure_rrtstar(bool informed, const double max_planning_time = 200; const auto rrtstar_param = fpa::RRTStarParam{update, informed, max_planning_time, mu, margin}; - auto clock_shrd_ptr = std::make_shared(RCL_ROS_TIME); - auto algo = std::make_unique( - planner_common_param, vehicle_shape, rrtstar_param, clock_shrd_ptr); + auto clock_ptr = std::make_shared(RCL_ROS_TIME); + auto algo = + std::make_unique(planner_common_param, vehicle_shape, rrtstar_param, clock_ptr); return algo; } diff --git a/planning/autoware_path_smoother/src/elastic_band.cpp b/planning/autoware_path_smoother/src/elastic_band.cpp index 0bec4e46c8b42..0bdf83c9d3b7c 100644 --- a/planning/autoware_path_smoother/src/elastic_band.cpp +++ b/planning/autoware_path_smoother/src/elastic_band.cpp @@ -34,9 +34,9 @@ Eigen::SparseMatrix makePMatrix(const int num_points) { std::vector> triplet_vec; const auto assign_value_to_triplet_vec = - [&](const double row, const double colum, const double value) { - triplet_vec.push_back(Eigen::Triplet(row, colum, value)); - triplet_vec.push_back(Eigen::Triplet(row + num_points, colum + num_points, value)); + [&](const double row, const double column, const double value) { + triplet_vec.push_back(Eigen::Triplet(row, column, value)); + triplet_vec.push_back(Eigen::Triplet(row + num_points, column + num_points, value)); }; for (int r = 0; r < num_points; ++r) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp index b694c8aaa2e3e..402f3c1d22cc7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp @@ -938,7 +938,7 @@ std::vector IntersectionModule::generateDetectionLan if (detection_lanelets.empty()) { // NOTE(soblin): due to the above filtering detection_lanelets may be empty or do not contain // conflicting_detection_lanelets - // OK to return empty detction_divsions + // OK to return empty detection_divisions return detection_divisions; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp index d9ef145eb5ce9..6ee31c3712b47 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp @@ -89,7 +89,7 @@ TEST(TestUtil, retrievePathsBackward) } /* - TOOD(Mamoru Sobue): instantiating intersection_module and PlannerData is a messy + TODO(Mamoru Sobue): instantiating intersection_module and PlannerData is a messy class TestWithMap : public ::testing::Test { protected: diff --git a/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp b/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp index 6c5f43e929766..caf50473cde18 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp @@ -103,9 +103,9 @@ TEST(splineTransform, benchFrenet) EXPECT_NEAR(frenet_naive.d, frenet_lut.d, precision); } std::cout << "size = " << size << std::endl; - std::cout << "\tnaive: " << std::chrono::duration_cast(naive).count() - << "ms\n"; - std::cout << "\tlut : " << std::chrono::duration_cast(lut).count() + std::cout << "\t naive: " + << std::chrono::duration_cast(naive).count() << "ms\n"; + std::cout << "\t lut : " << std::chrono::duration_cast(lut).count() << "ms\n"; } } diff --git a/simulator/autoware_carla_interface/README.md b/simulator/autoware_carla_interface/README.md index a44cb4708b5c3..2513364178693 100644 --- a/simulator/autoware_carla_interface/README.md +++ b/simulator/autoware_carla_interface/README.md @@ -136,14 +136,14 @@ The maps provided by the Carla Simulator ([Carla Lanelet2 Maps](https://bitbucke - Options to Modify the Map - A. Create a New Map from Scratch - - Use the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/) to create a new map. + - Use the [TIER IV Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/) to create a new map. - B. Modify the Existing Carla Lanelet2 Maps - Adjust the longitude and latitude of the [Carla Lanelet2 Maps](https://bitbucket.org/carla-simulator/autoware-contents/src/master/maps/) to align with the PCD (origin). - Use this [tool](https://github.com/mraditya01/offset_lanelet2/tree/main) to modify the coordinates. - - Snap Lanelet with PCD and add the traffic lights using the [Tier4 Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/). + - Snap Lanelet with PCD and add the traffic lights using the [TIER IV Vector Map Builder](https://tools.tier4.jp/feature/vector_map_builder_ll2/). -- When using the Tier4 Vector Map Builder, you must convert the PCD format from `binary_compressed` to `ascii`. You can use `pcl_tools` for this conversion. +- When using the TIER IV Vector Map Builder, you must convert the PCD format from `binary_compressed` to `ascii`. You can use `pcl_tools` for this conversion. - For reference, an example of Town01 with added traffic lights at one intersection can be downloaded [here](https://drive.google.com/drive/folders/1QFU0p3C8NW71sT5wwdnCKXoZFQJzXfTG?usp=sharing). ## Tips From 90fb05f72cb8c967a2a2399340c0957d18019842 Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Mon, 2 Dec 2024 15:35:09 +0900 Subject: [PATCH 193/273] feat(tier4_state_rviz_plugin): check for abrupt deceleration (#9474) * add abrupt deceleration checking feature to velocity steering factors panel Signed-off-by: mitukou1109 * use spin box instead of slider & change layout Signed-off-by: mitukou1109 * set minimum input to 0.0 Signed-off-by: mitukou1109 * change accent color to Freak Pink Signed-off-by: mitukou1109 --------- Signed-off-by: mitukou1109 --- common/tier4_state_rviz_plugin/package.xml | 1 + .../velocity_steering_factors_panel.hpp | 17 +++++- .../src/velocity_steering_factors_panel.cpp | 57 ++++++++++++++++++- 3 files changed, 71 insertions(+), 4 deletions(-) diff --git a/common/tier4_state_rviz_plugin/package.xml b/common/tier4_state_rviz_plugin/package.xml index aa7f5fe41c295..14ad8a22a52e2 100644 --- a/common/tier4_state_rviz_plugin/package.xml +++ b/common/tier4_state_rviz_plugin/package.xml @@ -14,6 +14,7 @@ ament_index_cpp autoware_adapi_v1_msgs + autoware_motion_utils autoware_vehicle_msgs libqt5-core libqt5-gui diff --git a/common/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp b/common/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp index 70f35ed3793ab..81677a69eb66f 100644 --- a/common/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp @@ -17,11 +17,10 @@ #ifndef VELOCITY_STEERING_FACTORS_PANEL_HPP_ #define VELOCITY_STEERING_FACTORS_PANEL_HPP_ +#include #include #include #include -#include -#include #include #include #include @@ -29,6 +28,8 @@ #include #include #include +#include +#include #include @@ -49,6 +50,11 @@ class VelocitySteeringFactorsPanel : public rviz_common::Panel void onInitialize() override; protected: + static constexpr double JERK_DEFAULT = 1.0; + static constexpr double DECEL_LIMIT_DEFAULT = 1.0; + + static constexpr QColor COLOR_FREAK_PINK = {255, 0, 108}; + // Layout QGroupBox * makeVelocityFactorsGroup(); QGroupBox * makeSteeringFactorsGroup(); @@ -58,7 +64,14 @@ class VelocitySteeringFactorsPanel : public rviz_common::Panel // Planning QTableWidget * velocity_factors_table_{nullptr}; QTableWidget * steering_factors_table_{nullptr}; + QDoubleSpinBox * jerk_input_{nullptr}; + QDoubleSpinBox * decel_limit_input_{nullptr}; + + nav_msgs::msg::Odometry::ConstSharedPtr kinematic_state_; + geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr acceleration_; + rclcpp::Subscription::SharedPtr sub_kinematic_state_; + rclcpp::Subscription::SharedPtr sub_acceleration_; rclcpp::Subscription::SharedPtr sub_velocity_factors_; rclcpp::Subscription::SharedPtr sub_steering_factors_; diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp index b7ea26e2c6895..fab40fe5a2214 100644 --- a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include @@ -46,7 +47,8 @@ QGroupBox * VelocitySteeringFactorsPanel::makeVelocityFactorsGroup() auto vertical_header = new QHeaderView(Qt::Vertical); vertical_header->hide(); auto horizontal_header = new QHeaderView(Qt::Horizontal); - horizontal_header->setSectionResizeMode(QHeaderView::Stretch); + horizontal_header->setSectionResizeMode(QHeaderView::ResizeToContents); + horizontal_header->setStretchLastSection(true); auto header_labels = QStringList({"Type", "Status", "Distance [m]", "Detail"}); velocity_factors_table_ = new QTableWidget(); @@ -54,7 +56,27 @@ QGroupBox * VelocitySteeringFactorsPanel::makeVelocityFactorsGroup() velocity_factors_table_->setHorizontalHeaderLabels(header_labels); velocity_factors_table_->setVerticalHeader(vertical_header); velocity_factors_table_->setHorizontalHeader(horizontal_header); - grid->addWidget(velocity_factors_table_, 0, 0); + grid->addWidget(velocity_factors_table_, 0, 0, 4, 1); + + auto * jerk_label = new QLabel("Jerk"); + grid->addWidget(jerk_label, 0, 1); + + jerk_input_ = new QDoubleSpinBox; + jerk_input_->setMinimum(0.0); + jerk_input_->setValue(JERK_DEFAULT); + jerk_input_->setSingleStep(0.1); + jerk_input_->setSuffix(" [m/s\u00B3]"); + grid->addWidget(jerk_input_, 1, 1); + + auto * decel_limit_label = new QLabel("Decel limit"); + grid->addWidget(decel_limit_label, 2, 1); + + decel_limit_input_ = new QDoubleSpinBox; + decel_limit_input_->setMinimum(0.0); + decel_limit_input_->setValue(DECEL_LIMIT_DEFAULT); + decel_limit_input_->setSingleStep(0.1); + decel_limit_input_->setSuffix(" [m/s\u00B2]"); + grid->addWidget(decel_limit_input_, 3, 1); group->setLayout(grid); return group; @@ -90,6 +112,17 @@ void VelocitySteeringFactorsPanel::onInitialize() raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); // Planning + sub_kinematic_state_ = raw_node_->create_subscription( + "/localization/kinematic_state", 10, + [this](const nav_msgs::msg::Odometry::ConstSharedPtr msg) { kinematic_state_ = msg; }); + + sub_acceleration_ = + raw_node_->create_subscription( + "/localization/acceleration", 10, + [this](const geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr msg) { + acceleration_ = msg; + }); + sub_velocity_factors_ = raw_node_->create_subscription( "/api/planning/velocity_factors", 10, std::bind(&VelocitySteeringFactorsPanel::onVelocityFactors, this, _1)); @@ -155,6 +188,26 @@ void VelocitySteeringFactorsPanel::onVelocityFactors(const VelocityFactorArray:: label->setAlignment(Qt::AlignCenter); velocity_factors_table_->setCellWidget(i, 3, label); } + + const auto row_background = [&]() -> QBrush { + if (!kinematic_state_ || !acceleration_) { + return {}; + } + const auto & current_vel = kinematic_state_->twist.twist.linear.x; + const auto & current_acc = acceleration_->accel.accel.linear.x; + const auto acc_min = -decel_limit_input_->value(); + const auto jerk_acc = jerk_input_->value(); + const auto decel_dist = autoware::motion_utils::calcDecelDistWithJerkAndAccConstraints( + current_vel, 0., current_acc, acc_min, jerk_acc, -jerk_acc); + if (decel_dist > e.distance && e.distance >= 0 && e.status == VelocityFactor::APPROACHING) { + return COLOR_FREAK_PINK; + } + return {}; + }(); + for (int j = 0; j < velocity_factors_table_->columnCount(); j++) { + velocity_factors_table_->setItem(i, j, new QTableWidgetItem); + velocity_factors_table_->item(i, j)->setBackground(row_background); + } } velocity_factors_table_->update(); } From 9fac5544bcecaf14c44310435a44dd2820b6a9dc Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Dec 2024 15:48:40 +0900 Subject: [PATCH 194/273] chore(blind_spot): divide headers to include/ (#9534) Signed-off-by: Mamoru Sobue --- .../behavior_velocity_blind_spot_module}/manager.hpp | 8 ++++---- .../behavior_velocity_blind_spot_module}/scene.hpp | 6 +++--- .../package.xml | 1 + .../src/debug.cpp | 2 +- .../src/decisions.cpp | 2 +- .../src/manager.cpp | 2 +- .../src/scene.cpp | 2 +- 7 files changed, 12 insertions(+), 11 deletions(-) rename planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/{src => include/autoware/behavior_velocity_blind_spot_module}/manager.hpp (85%) rename planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/{src => include/autoware/behavior_velocity_blind_spot_module}/scene.hpp (97%) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp similarity index 85% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.hpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp index edc4ea502b396..f296ad03cbac6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/manager.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MANAGER_HPP_ -#define MANAGER_HPP_ +#ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__MANAGER_HPP_ +#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__MANAGER_HPP_ -#include "scene.hpp" +#include "autoware/behavior_velocity_blind_spot_module/scene.hpp" #include #include @@ -52,4 +52,4 @@ class BlindSpotModulePlugin : public PluginWrapper } // namespace autoware::behavior_velocity_planner -#endif // MANAGER_HPP_ +#endif // AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__MANAGER_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp similarity index 97% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.hpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp index 0c913964332ab..434bb6b9a0696 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SCENE_HPP_ -#define SCENE_HPP_ +#ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_ +#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_ #include #include @@ -241,4 +241,4 @@ class BlindSpotModule : public SceneModuleInterface }; } // namespace autoware::behavior_velocity_planner -#endif // SCENE_HPP_ +#endif // AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml index de5d791c06161..b484c6a66cbac 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml @@ -8,6 +8,7 @@ Mamoru Sobue Tomoya Kimura Shumpei Wakabayashi + Yukinari Hisaki Apache License 2.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp index 714280daad38e..06ed75c99124b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "scene.hpp" +#include "autoware/behavior_velocity_blind_spot_module/scene.hpp" #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp index 116050871c722..6a3d542600b3c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "scene.hpp" +#include "autoware/behavior_velocity_blind_spot_module/scene.hpp" #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp index 4e6cebeef2162..5e05de72e0cab 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "manager.hpp" +#include "autoware/behavior_velocity_blind_spot_module/manager.hpp" #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp index 2eb54f91a3e26..c6cc8cf4a3db8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "scene.hpp" +#include "autoware/behavior_velocity_blind_spot_module/scene.hpp" #include #include From 7b7db7a4ddf3998b4032161df0c045b6553d9cb6 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Dec 2024 19:03:20 +0900 Subject: [PATCH 195/273] feat(behavior_velocity_planner)!: remove stop_reason (#9452) Signed-off-by: Mamoru Sobue --- .../scene.hpp | 10 +- .../src/decisions.cpp | 22 +--- .../src/scene.cpp | 18 ++-- .../src/scene_crosswalk.cpp | 8 +- .../src/scene_crosswalk.hpp | 4 +- .../src/scene.cpp | 20 +--- .../src/scene.hpp | 2 +- .../src/scene_intersection.cpp | 101 +++--------------- .../src/scene_intersection.hpp | 7 +- .../src/scene_merge_from_private_road.cpp | 6 +- .../src/scene_merge_from_private_road.hpp | 2 +- .../src/scene.cpp | 29 ++--- .../src/scene.hpp | 8 +- .../src/scene_no_stopping_area.cpp | 19 +--- .../src/scene_no_stopping_area.hpp | 2 +- .../src/scene_occlusion_spot.cpp | 3 +- .../src/scene_occlusion_spot.hpp | 2 +- .../src/node.cpp | 3 - .../src/node.hpp | 1 - .../src/planner_manager.cpp | 50 --------- .../src/planner_manager.hpp | 4 +- .../plugin_interface.hpp | 1 - .../plugin_wrapper.hpp | 4 - .../scene_module_interface.hpp | 13 +-- .../utilization/util.hpp | 7 -- .../src/scene_module_interface.cpp | 19 +--- .../src/utilization/util.cpp | 12 --- .../src/scene.cpp | 3 +- .../src/scene.hpp | 2 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 2 +- .../src/scene.cpp | 13 +-- .../src/scene.hpp | 4 +- .../src/scene.cpp | 3 +- .../src/scene.hpp | 3 +- .../src/manager.cpp | 19 +--- .../src/scene.cpp | 24 +---- .../src/scene.hpp | 4 +- .../src/scene.cpp | 30 ++---- .../src/scene.hpp | 10 +- .../src/scene_walkway.cpp | 7 +- .../src/scene_walkway.hpp | 2 +- 42 files changed, 90 insertions(+), 416 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp index 434bb6b9a0696..e9542feaccfd1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp @@ -114,7 +114,7 @@ class BlindSpotModule : public SceneModuleInterface * @brief plan go-stop velocity at traffic crossing with collision check between reference path * and object predicted path */ - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; std::vector createVirtualWalls() override; @@ -133,7 +133,7 @@ class BlindSpotModule : public SceneModuleInterface // Parameter void initializeRTCStatus(); - BlindSpotDecision modifyPathVelocityDetail(PathWithLaneId * path, StopReason * stop_reason); + BlindSpotDecision modifyPathVelocityDetail(PathWithLaneId * path); // setSafe(), setDistance() void setRTCStatus( const BlindSpotDecision & decision, const tier4_planning_msgs::msg::PathWithLaneId & path); @@ -141,12 +141,10 @@ class BlindSpotModule : public SceneModuleInterface void setRTCStatusByDecision( const Decision & decision, const tier4_planning_msgs::msg::PathWithLaneId & path); // stop/GO - void reactRTCApproval( - const BlindSpotDecision & decision, PathWithLaneId * path, StopReason * stop_reason); + void reactRTCApproval(const BlindSpotDecision & decision, PathWithLaneId * path); template void reactRTCApprovalByDecision( - const Decision & decision, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason); + const Decision & decision, tier4_planning_msgs::msg::PathWithLaneId * path); std::optional generateInterpolatedPathInfo( const tier4_planning_msgs::msg::PathWithLaneId & input_path) const; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp index 6a3d542600b3c..64e1435167a89 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp @@ -33,8 +33,7 @@ void BlindSpotModule::setRTCStatusByDecision( template void BlindSpotModule::reactRTCApprovalByDecision( [[maybe_unused]] const T & decision, - [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] StopReason * stop_reason) + [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path) { static_assert("Unsupported type passed to reactRTCApprovalByDecision"); } @@ -53,8 +52,7 @@ void BlindSpotModule::setRTCStatusByDecision( template <> void BlindSpotModule::reactRTCApprovalByDecision( [[maybe_unused]] const InternalError & decision, - [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] StopReason * stop_reason) + [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path) { return; } @@ -73,8 +71,7 @@ void BlindSpotModule::setRTCStatusByDecision( template <> void BlindSpotModule::reactRTCApprovalByDecision( [[maybe_unused]] const OverPassJudge & decision, - [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] StopReason * stop_reason) + [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path) { return; } @@ -95,8 +92,7 @@ void BlindSpotModule::setRTCStatusByDecision( template <> void BlindSpotModule::reactRTCApprovalByDecision( - const Unsafe & decision, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason) + const Unsafe & decision, tier4_planning_msgs::msg::PathWithLaneId * path) { if (!isActivated()) { constexpr double stop_vel = 0.0; @@ -104,11 +100,7 @@ void BlindSpotModule::reactRTCApprovalByDecision( debug_data_.virtual_wall_pose = planning_utils::getAheadPose( decision.stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); - tier4_planning_msgs::msg::StopFactor stop_factor; const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose; - stop_factor.stop_pose = stop_pose; - stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data_.conflicting_targets); - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); } @@ -131,7 +123,7 @@ void BlindSpotModule::setRTCStatusByDecision( template <> void BlindSpotModule::reactRTCApprovalByDecision( - const Safe & decision, tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason) + const Safe & decision, tier4_planning_msgs::msg::PathWithLaneId * path) { if (!isActivated()) { constexpr double stop_vel = 0.0; @@ -139,11 +131,7 @@ void BlindSpotModule::reactRTCApprovalByDecision( debug_data_.virtual_wall_pose = planning_utils::getAheadPose( decision.stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); - tier4_planning_msgs::msg::StopFactor stop_factor; const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose; - stop_factor.stop_pose = stop_pose; - stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data_.conflicting_targets); - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp index c6cc8cf4a3db8..b5cbbfdf354bb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp @@ -64,8 +64,7 @@ void BlindSpotModule::initializeRTCStatus() setDistance(std::numeric_limits::lowest()); } -BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail( - PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) +BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail(PathWithLaneId * path) { if (planner_param_.use_pass_judge_line && is_over_pass_judge_line_) { return OverPassJudge{"already over the pass judge line. no plan needed."}; @@ -160,26 +159,23 @@ void BlindSpotModule::setRTCStatus( decision); } -void BlindSpotModule::reactRTCApproval( - const BlindSpotDecision & decision, PathWithLaneId * path, StopReason * stop_reason) +void BlindSpotModule::reactRTCApproval(const BlindSpotDecision & decision, PathWithLaneId * path) { std::visit( - VisitorSwitch{[&](const auto & sub_decision) { - reactRTCApprovalByDecision(sub_decision, path, stop_reason); - }}, + VisitorSwitch{ + [&](const auto & sub_decision) { reactRTCApprovalByDecision(sub_decision, path); }}, decision); } -bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path) { debug_data_ = DebugData(); - *stop_reason = planning_utils::initializeStopReason(StopReason::BLIND_SPOT); initializeRTCStatus(); - const auto decision = modifyPathVelocityDetail(path, stop_reason); + const auto decision = modifyPathVelocityDetail(path); const auto & input_path = *path; setRTCStatus(decision, input_path); - reactRTCApproval(decision, path, stop_reason); + reactRTCApproval(decision, path); return true; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index 51a0b4aa23fde..b0ea73a2781d4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -201,7 +201,7 @@ CrosswalkModule::CrosswalkModule( node.create_publisher("~/debug/collision_info", 1); } -bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path) { if (path->points.size() < 2) { RCLCPP_DEBUG(logger_, "Do not interpolate because path size is less than 2."); @@ -213,7 +213,6 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto logger_, planner_param_.show_processing_time, "=========== module_id: %ld ===========", module_id_); - *stop_reason = planning_utils::initializeStopReason(StopReason::CROSSWALK); const auto & ego_pos = planner_data_->current_odometry->pose.position; const auto objects_ptr = planner_data_->predicted_objects; @@ -274,7 +273,7 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto if (isActivated()) { planGo(*path, nearest_stop_factor); } else { - planStop(*path, nearest_stop_factor, default_stop_pose, stop_reason); + planStop(*path, nearest_stop_factor, default_stop_pose); } recordTime(4); @@ -1353,7 +1352,7 @@ void CrosswalkModule::planGo( void CrosswalkModule::planStop( PathWithLaneId & ego_path, const std::optional & nearest_stop_factor, - const std::optional & default_stop_pose, StopReason * stop_reason) + const std::optional & default_stop_pose) { // Calculate stop factor auto stop_factor = [&]() -> std::optional { @@ -1376,7 +1375,6 @@ void CrosswalkModule::planStop( // Plan stop insertDecelPointWithDebugInfo(stop_factor->stop_pose.position, 0.0, ego_path); - planning_utils::appendStopReason(*stop_factor, stop_reason); velocity_factor_.set( ego_path.points, planner_data_->current_odometry->pose, stop_factor->stop_pose, VelocityFactor::UNKNOWN); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index de696aa670ad3..d27aebe42d459 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -336,7 +336,7 @@ class CrosswalkModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; @@ -399,7 +399,7 @@ class CrosswalkModule : public SceneModuleInterface void planStop( PathWithLaneId & ego_path, const std::optional & nearest_stop_factor, - const std::optional & default_stop_pose, StopReason * stop_reason); + const std::optional & default_stop_pose); // minor functions std::pair getAttentionRange( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp index abbb818f2b042..61b3b185999d8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp @@ -47,7 +47,7 @@ DetectionAreaModule::DetectionAreaModule( velocity_factor_.init(PlanningBehavior::USER_DEFINED_DETECTION_AREA); } -bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path) { // Store original path const auto original_path = *path; @@ -55,7 +55,6 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason * // Reset data debug_data_ = DebugData(); debug_data_.base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; - *stop_reason = planning_utils::initializeStopReason(StopReason::DETECTION_AREA); // Find obstacles in detection area const auto obstacle_points = detection_area::get_obstacle_points( @@ -184,28 +183,11 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason * // Create StopReason { - StopFactor stop_factor{}; - stop_factor.stop_pose = stop_point->second; - stop_factor.stop_factor_points = obstacle_points; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_point->second, VelocityFactor::UNKNOWN); } - // Create legacy StopReason - { - const double stop_path_point_distance = autoware::motion_utils::calcSignedArcLength( - path->points, 0, stop_pose.position, stop_point->first); - - if ( - !first_stop_path_point_distance_ || - stop_path_point_distance < first_stop_path_point_distance_.value()) { - debug_data_.first_stop_pose = stop_point->second; - first_stop_path_point_distance_ = stop_path_point_distance; - } - } - return true; } } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp index 46bb46bcdeb61..9224cf4624687 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.hpp @@ -70,7 +70,7 @@ class DetectionAreaModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index 8115f52437a04..cedc3c41e8165 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -91,14 +91,13 @@ IntersectionModule::IntersectionModule( "~/debug/intersection/object_ttc", 1); } -bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path) { debug_data_ = DebugData(); - *stop_reason = planning_utils::initializeStopReason(StopReason::INTERSECTION); initializeRTCStatus(); - const auto decision_result = modifyPathVelocityDetail(path, stop_reason); + const auto decision_result = modifyPathVelocityDetail(path); prev_decision_result_ = decision_result; { @@ -110,7 +109,7 @@ bool IntersectionModule::modifyPathVelocity(PathWithLaneId * path, StopReason * prepareRTCStatus(decision_result, *path); - reactRTCApproval(decision_result, path, stop_reason); + reactRTCApproval(decision_result, path); return true; } @@ -145,8 +144,7 @@ static std::string formatOcclusionType(const IntersectionModule::OcclusionType & return "RTCOccluded"; } -DecisionResult IntersectionModule::modifyPathVelocityDetail( - PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) +DecisionResult IntersectionModule::modifyPathVelocityDetail(PathWithLaneId * path) { const auto prepare_data = prepareIntersectionData(path); if (!prepare_data) { @@ -683,7 +681,6 @@ void prepareRTCByDecisionResult( *occlusion_safety = true; *occlusion_distance = autoware::motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); - return; } void IntersectionModule::prepareRTCStatus( @@ -711,7 +708,6 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] StopReason * stop_reason, [[maybe_unused]] VelocityFactorInterface * velocity_factor, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { @@ -727,7 +723,6 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] StopReason * stop_reason, [[maybe_unused]] VelocityFactorInterface * velocity_factor, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { @@ -742,7 +737,6 @@ void reactRTCApprovalByDecisionResult( [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, [[maybe_unused]] const double baselink2front, [[maybe_unused]] tier4_planning_msgs::msg::PathWithLaneId * path, - [[maybe_unused]] StopReason * stop_reason, [[maybe_unused]] VelocityFactorInterface * velocity_factor, [[maybe_unused]] IntersectionModule::DebugData * debug_data) { @@ -755,8 +749,7 @@ void reactRTCApprovalByDecisionResult( const StuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, - IntersectionModule::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -770,10 +763,6 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data->unsafe_targets); - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -785,9 +774,6 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(occlusion_stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(occlusion_stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, path->points.at(occlusion_stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -802,8 +788,7 @@ void reactRTCApprovalByDecisionResult( const YieldStuckStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, - IntersectionModule::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -817,10 +802,6 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data->unsafe_targets); - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -835,8 +816,7 @@ void reactRTCApprovalByDecisionResult( const NonOccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, - IntersectionModule::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -848,9 +828,6 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -862,9 +839,6 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -878,8 +852,8 @@ void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, const FirstWaitBeforeOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, - tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + tier4_planning_msgs::msg::PathWithLaneId * path, VelocityFactorInterface * velocity_factor, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -891,9 +865,6 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_first_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -913,9 +884,6 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -929,8 +897,8 @@ void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, const PeekingTowardOcclusion & decision_result, const IntersectionModule::PlannerParam & planner_param, const double baselink2front, - tier4_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, - VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) + tier4_planning_msgs::msg::PathWithLaneId * path, VelocityFactorInterface * velocity_factor, + IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -955,9 +923,6 @@ void reactRTCApprovalByDecisionResult( debug_data->static_occlusion_with_traffic_light_timeout = decision_result.static_occlusion_timeout; { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(occlusion_peeking_stopline).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(occlusion_peeking_stopline).point.pose, VelocityFactor::UNKNOWN); @@ -969,9 +934,6 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -986,8 +948,7 @@ void reactRTCApprovalByDecisionResult( const OccludedCollisionStop & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, - IntersectionModule::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -999,9 +960,6 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -1017,9 +975,6 @@ void reactRTCApprovalByDecisionResult( debug_data->static_occlusion_with_traffic_light_timeout = decision_result.static_occlusion_timeout; { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -1034,8 +989,7 @@ void reactRTCApprovalByDecisionResult( const OccludedAbsenceTrafficLight & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, - IntersectionModule::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -1047,9 +1001,6 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -1061,9 +1012,6 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -1087,8 +1035,7 @@ void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, const Safe & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, - IntersectionModule::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -1099,9 +1046,6 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -1113,9 +1057,6 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -1130,8 +1071,7 @@ void reactRTCApprovalByDecisionResult( const FullyPrioritized & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason, VelocityFactorInterface * velocity_factor, - IntersectionModule::DebugData * debug_data) + VelocityFactorInterface * velocity_factor, IntersectionModule::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), @@ -1143,9 +1083,6 @@ void reactRTCApprovalByDecisionResult( debug_data->collision_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -1157,9 +1094,6 @@ void reactRTCApprovalByDecisionResult( debug_data->occlusion_stop_wall_pose = planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); @@ -1169,15 +1103,14 @@ void reactRTCApprovalByDecisionResult( } void IntersectionModule::reactRTCApproval( - const DecisionResult & decision_result, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason) + const DecisionResult & decision_result, tier4_planning_msgs::msg::PathWithLaneId * path) { const double baselink2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; std::visit( VisitorSwitch{[&](const auto & decision) { reactRTCApprovalByDecisionResult( activated_, occlusion_activated_, decision, planner_param_, baselink2front, path, - stop_reason, &velocity_factor_, &debug_data_); + &velocity_factor_, &debug_data_); }}, decision_result); return; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp index 8ffb4792f55db..b718dd84d33af 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -321,7 +321,7 @@ class IntersectionModule : public SceneModuleInterface * INTERSECTION_OCCLUSION. * @{ */ - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; /** @}*/ visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; @@ -504,7 +504,7 @@ class IntersectionModule : public SceneModuleInterface /** * @brief analyze traffic_light/occupancy/objects context and return DecisionResult */ - DecisionResult modifyPathVelocityDetail(PathWithLaneId * path, StopReason * stop_reason); + DecisionResult modifyPathVelocityDetail(PathWithLaneId * path); /** * @brief set RTC value according to calculated DecisionResult @@ -516,8 +516,7 @@ class IntersectionModule : public SceneModuleInterface * @brief act based on current RTC approval */ void reactRTCApproval( - const DecisionResult & decision_result, tier4_planning_msgs::msg::PathWithLaneId * path, - StopReason * stop_reason); + const DecisionResult & decision_result, tier4_planning_msgs::msg::PathWithLaneId * path); /** @}*/ private: diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index d5cd9ca587716..478576a5c6676 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -76,10 +76,9 @@ static std::optional getFirstConflictingLanelet( return std::nullopt; } -bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path) { debug_data_ = DebugData(); - *stop_reason = planning_utils::initializeStopReason(StopReason::MERGE_FROM_PRIVATE_ROAD); const auto input_path = *path; @@ -152,9 +151,6 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR planning_utils::setVelocityFromIndex(stopline_idx, v, path); /* get stop point and stop factor */ - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = debug_data_.stop_point_pose; - planning_utils::appendStopReason(stop_factor, stop_reason); const auto & stop_pose = path->points.at(stopline_idx).point.pose; velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index a69297adea881..dc8bf1a96a7a2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -67,7 +67,7 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface * @brief plan go-stop velocity at traffic crossing with collision check between reference path * and object predicted path */ - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp index c3af04bbd1d1f..8365251904b18 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp @@ -37,14 +37,12 @@ NoDrivableLaneModule::NoDrivableLaneModule( velocity_factor_.init(PlanningBehavior::NO_DRIVABLE_LANE); } -bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path) { if (path->points.empty()) { return false; } - *stop_reason = planning_utils::initializeStopReason(StopReason::NO_DRIVABLE_LANE); - const auto & ego_pos = planner_data_->current_odometry->pose.position; const auto & lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); const auto & no_drivable_lane = lanelet_map_ptr->laneletLayer.get(lane_id_); @@ -82,7 +80,7 @@ bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason RCLCPP_INFO(logger_, "Approaching "); } - handle_approaching_state(path, stop_reason); + handle_approaching_state(path); break; } @@ -92,7 +90,7 @@ bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason RCLCPP_INFO(logger_, "INSIDE_NO_DRIVABLE_LANE"); } - handle_inside_no_drivable_lane_state(path, stop_reason); + handle_inside_no_drivable_lane_state(path); break; } @@ -102,7 +100,7 @@ bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason RCLCPP_INFO(logger_, "STOPPED"); } - handle_stopped_state(path, stop_reason); + handle_stopped_state(path); break; } @@ -131,7 +129,7 @@ void NoDrivableLaneModule::handle_init_state() } } -void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path, StopReason * stop_reason) +void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path) { const double longitudinal_offset = -1.0 * (planner_param_.stop_margin + planner_data_->vehicle_info_.max_longitudinal_offset_m); @@ -163,11 +161,7 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path, StopR // Get stop point and stop factor { - tier4_planning_msgs::msg::StopFactor stop_factor; const auto & stop_pose = op_stop_pose.value(); - stop_factor.stop_pose = stop_pose; - stop_factor.stop_factor_points.push_back(stop_point); - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING); @@ -205,8 +199,7 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path, StopR } } -void NoDrivableLaneModule::handle_inside_no_drivable_lane_state( - PathWithLaneId * path, StopReason * stop_reason) +void NoDrivableLaneModule::handle_inside_no_drivable_lane_state(PathWithLaneId * path) { const auto & current_point = planner_data_->current_odometry->pose.position; const size_t current_seg_idx = findEgoSegmentIndex(path->points); @@ -216,11 +209,7 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state( // Get stop point and stop factor { - tier4_planning_msgs::msg::StopFactor stop_factor; const auto & stop_pose = autoware::universe_utils::getPose(path->points.at(0)); - stop_factor.stop_pose = stop_pose; - stop_factor.stop_factor_points.push_back(current_point); - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING); @@ -239,7 +228,7 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state( } } -void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path, StopReason * stop_reason) +void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path) { const auto & stopped_pose = autoware::motion_utils::calcLongitudinalOffsetPose( path->points, planner_data_->current_odometry->pose.position, 0.0); @@ -258,11 +247,7 @@ void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path, StopReaso // Get stop point and stop factor { - tier4_planning_msgs::msg::StopFactor stop_factor; const auto & stop_pose = ego_pos_on_path.pose; - stop_factor.stop_pose = stop_pose; - stop_factor.stop_factor_points.push_back(stop_pose.position); - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::STOPPED); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp index d9e6121a8ae51..d8c5e3e0425d1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.hpp @@ -57,7 +57,7 @@ class NoDrivableLaneModule : public SceneModuleInterface const int64_t module_id, const int64_t lane_id, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; @@ -79,9 +79,9 @@ class NoDrivableLaneModule : public SceneModuleInterface double distance_ego_first_intersection{}; void handle_init_state(); - void handle_approaching_state(PathWithLaneId * path, StopReason * stop_reason); - void handle_inside_no_drivable_lane_state(PathWithLaneId * path, StopReason * stop_reason); - void handle_stopped_state(PathWithLaneId * path, StopReason * stop_reason); + void handle_approaching_state(PathWithLaneId * path); + void handle_inside_no_drivable_lane_state(PathWithLaneId * path); + void handle_stopped_state(PathWithLaneId * path); void initialize_debug_data( const lanelet::Lanelet & no_drivable_lane, const geometry_msgs::msg::Point & ego_pos); }; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp index bac91d6ca92fd..3769aed71a1ec 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp @@ -52,7 +52,7 @@ NoStoppingAreaModule::NoStoppingAreaModule( state_machine_.setMarginTime(planner_param_.state_clear_time); } -bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path) { // Store original path const auto original_path = *path; @@ -64,7 +64,6 @@ bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason // Reset data debug_data_ = no_stopping_area::DebugData(); debug_data_.base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; - *stop_reason = planning_utils::initializeStopReason(StopReason::NO_STOPPING_AREA); const no_stopping_area::EgoData ego_data(*planner_data_); @@ -142,27 +141,11 @@ bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path, StopReason // Create StopReason { - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = stop_point->second; - stop_factor.stop_factor_points = debug_data_.stuck_points; - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_point->second, VelocityFactor::UNKNOWN); } - // Create legacy StopReason - { - const double stop_path_point_distance = autoware::motion_utils::calcSignedArcLength( - path->points, 0, stop_pose.position, stop_point->first); - - if ( - !first_stop_path_point_distance_ || - stop_path_point_distance < first_stop_path_point_distance_.value()) { - debug_data_.first_stop_pose = stop_point->second; - first_stop_path_point_distance_ = stop_path_point_distance; - } - } } else if (state_machine_.getState() == StateMachine::State::GO) { // reset pass judge if current state is go pass_judge_.is_stoppable = true; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp index 886c8f04dc702..51f3a0d261ebd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.hpp @@ -59,7 +59,7 @@ class NoStoppingAreaModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index 24b9d10e09830..dfc2dca7afc21 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -82,8 +82,7 @@ OcclusionSpotModule::OcclusionSpotModule( } } -bool OcclusionSpotModule::modifyPathVelocity( - PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) +bool OcclusionSpotModule::modifyPathVelocity(PathWithLaneId * path) { if (param_.is_show_processing_time) stop_watch_.tic("total_processing_time"); debug_data_.resetData(); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp index b83051fb6b6ec..35c409a9c459b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.hpp @@ -53,7 +53,7 @@ class OcclusionSpotModule : public SceneModuleInterface /** * @brief plan occlusion spot velocity at unknown area in occupancy grid */ - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index 5f4d0606abfc6..2b921028c499a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -79,8 +79,6 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio // Publishers path_pub_ = this->create_publisher("~/output/path", 1); - stop_reason_diag_pub_ = - this->create_publisher("~/output/stop_reason", 1); debug_viz_pub_ = this->create_publisher("~/debug/path", 1); // Parameters @@ -327,7 +325,6 @@ void BehaviorVelocityPlannerNode::onTrigger( path_pub_->publish(output_path_msg); published_time_publisher_->publish_if_subscribed(path_pub_, output_path_msg.header.stamp); - stop_reason_diag_pub_->publish(planner_manager_.getStopReasonDiag()); if (debug_viz_pub_->get_subscription_count() > 0) { publishDebugMarker(output_path_msg); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp index d72b90d41e8f4..e260f582aae60 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.hpp @@ -113,7 +113,6 @@ class BehaviorVelocityPlannerNode : public rclcpp::Node // publisher rclcpp::Publisher::SharedPtr path_pub_; - rclcpp::Publisher::SharedPtr stop_reason_diag_pub_; rclcpp::Publisher::SharedPtr debug_viz_pub_; void publishDebugMarker(const autoware_planning_msgs::msg::Path & path); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp index 05aa4868249f3..4820c340058ff 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp @@ -25,34 +25,6 @@ namespace autoware::behavior_velocity_planner { -namespace -{ -std::string jsonDumpsPose(const geometry_msgs::msg::Pose & pose) -{ - const std::string json_dumps_pose = - (boost::format( - R"({"position":{"x":%lf,"y":%lf,"z":%lf},"orientation":{"w":%lf,"x":%lf,"y":%lf,"z":%lf}})") % - pose.position.x % pose.position.y % pose.position.z % pose.orientation.w % pose.orientation.x % - pose.orientation.y % pose.orientation.z) - .str(); - return json_dumps_pose; -} - -diagnostic_msgs::msg::DiagnosticStatus makeStopReasonDiag( - const std::string & stop_reason, const geometry_msgs::msg::Pose & stop_pose) -{ - diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag; - diagnostic_msgs::msg::KeyValue stop_reason_diag_kv; - stop_reason_diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK; - stop_reason_diag.name = "stop_reason"; - stop_reason_diag.message = stop_reason; - stop_reason_diag_kv.key = "stop_pose"; - stop_reason_diag_kv.value = jsonDumpsPose(stop_pose); - stop_reason_diag.values.push_back(stop_reason_diag_kv); - return stop_reason_diag; -} -} // namespace - BehaviorVelocityPlannerManager::BehaviorVelocityPlannerManager() : plugin_loader_( "autoware_behavior_velocity_planner", "autoware::behavior_velocity_planner::PluginInterface") @@ -107,34 +79,12 @@ tier4_planning_msgs::msg::PathWithLaneId BehaviorVelocityPlannerManager::planPat { tier4_planning_msgs::msg::PathWithLaneId output_path_msg = input_path_msg; - double first_stop_path_point_distance = - autoware::motion_utils::calcArcLength(output_path_msg.points); - std::string stop_reason_msg("path_end"); - for (const auto & plugin : scene_manager_plugins_) { plugin->updateSceneModuleInstances(planner_data, input_path_msg); plugin->plan(&output_path_msg); - const std::optional firstStopPathPointDistance = - plugin->getFirstStopPathPointDistance(); - - if (firstStopPathPointDistance.has_value()) { - if (firstStopPathPointDistance.value() < first_stop_path_point_distance) { - first_stop_path_point_distance = firstStopPathPointDistance.value(); - stop_reason_msg = plugin->getModuleName(); - } - } } - const geometry_msgs::msg::Pose stop_pose = autoware::motion_utils::calcInterpolatedPose( - output_path_msg.points, first_stop_path_point_distance); - - stop_reason_diag_ = makeStopReasonDiag(stop_reason_msg, stop_pose); - return output_path_msg; } -diagnostic_msgs::msg::DiagnosticStatus BehaviorVelocityPlannerManager::getStopReasonDiag() const -{ - return stop_reason_diag_; -} } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.hpp index abeab16dd71cb..fddd658cef06e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.hpp @@ -46,14 +46,12 @@ class BehaviorVelocityPlannerManager void launchScenePlugin(rclcpp::Node & node, const std::string & name); void removeScenePlugin(rclcpp::Node & node, const std::string & name); + // cppcheck-suppress functionConst tier4_planning_msgs::msg::PathWithLaneId planPathVelocity( const std::shared_ptr & planner_data, const tier4_planning_msgs::msg::PathWithLaneId & input_path_msg); - diagnostic_msgs::msg::DiagnosticStatus getStopReasonDiag() const; - private: - diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag_; pluginlib::ClassLoader plugin_loader_; std::vector> scene_manager_plugins_; }; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_interface.hpp index 5f6549f1e4492..4867b14cbb806 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_interface.hpp @@ -34,7 +34,6 @@ class PluginInterface virtual void updateSceneModuleInstances( const std::shared_ptr & planner_data, const tier4_planning_msgs::msg::PathWithLaneId & path) = 0; - virtual std::optional getFirstStopPathPointDistance() = 0; virtual const char * getModuleName() = 0; }; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_wrapper.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_wrapper.hpp index 0392bf24d3a36..44a00072a0be4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_wrapper.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/plugin_wrapper.hpp @@ -38,10 +38,6 @@ class PluginWrapper : public PluginInterface { scene_manager_->updateSceneModuleInstances(planner_data, path); } - std::optional getFirstStopPathPointDistance() override - { - return scene_manager_->getFirstStopPathPointDistance(); - } const char * getModuleName() override { return scene_manager_->getModuleName(); } private: diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index e39cfb3a5144d..5725ebe51b4a5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -30,8 +30,6 @@ #include #include #include -#include -#include #include #include #include @@ -61,8 +59,6 @@ using autoware::universe_utils::getOrDeclareParameter; using builtin_interfaces::msg::Time; using tier4_debug_msgs::msg::Float64Stamped; using tier4_planning_msgs::msg::PathWithLaneId; -using tier4_planning_msgs::msg::StopFactor; -using tier4_planning_msgs::msg::StopReason; using tier4_rtc_msgs::msg::Module; using tier4_rtc_msgs::msg::State; using unique_identifier_msgs::msg::UUID; @@ -87,7 +83,7 @@ class SceneModuleInterface const int64_t module_id, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock); virtual ~SceneModuleInterface() = default; - virtual bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) = 0; + virtual bool modifyPathVelocity(PathWithLaneId * path) = 0; virtual visualization_msgs::msg::MarkerArray createDebugMarkerArray() = 0; virtual std::vector createVirtualWalls() = 0; @@ -116,8 +112,6 @@ class SceneModuleInterface std::shared_ptr getTimeKeeper() { return time_keeper_; } - std::optional getFirstStopPathPointDistance() { return first_stop_path_point_distance_; } - void setActivation(const bool activated) { activated_ = activated; } void setRTCEnabled(const bool enable_rtc) { rtc_enabled_ = enable_rtc; } bool isActivated() const { return activated_; } @@ -139,7 +133,6 @@ class SceneModuleInterface rclcpp::Clock::SharedPtr clock_; std::shared_ptr planner_data_; std::optional infrastructure_command_; - std::optional first_stop_path_point_distance_; autoware::motion_utils::VelocityFactorInterface velocity_factor_; std::vector objects_of_interest_; mutable std::shared_ptr time_keeper_; @@ -174,8 +167,6 @@ class SceneModuleManagerInterface virtual const char * getModuleName() = 0; - std::optional getFirstStopPathPointDistance() { return first_stop_path_point_distance_; } - void updateSceneModuleInstances( const std::shared_ptr & planner_data, const tier4_planning_msgs::msg::PathWithLaneId & path); @@ -208,7 +199,6 @@ class SceneModuleManagerInterface std::shared_ptr planner_data_; autoware::motion_utils::VirtualWallMarkerCreator virtual_wall_marker_creator_; - std::optional first_stop_path_point_distance_; rclcpp::Node & node_; rclcpp::Clock::SharedPtr clock_; // Debug @@ -217,7 +207,6 @@ class SceneModuleManagerInterface rclcpp::Publisher::SharedPtr pub_virtual_wall_; rclcpp::Publisher::SharedPtr pub_debug_; rclcpp::Publisher::SharedPtr pub_debug_path_; - rclcpp::Publisher::SharedPtr pub_stop_reason_; rclcpp::Publisher::SharedPtr pub_velocity_factor_; rclcpp::Publisher::SharedPtr diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp index 5f1c17ea1b815..4cbf820268df5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp @@ -21,7 +21,6 @@ #include #include #include -#include #include #include @@ -65,8 +64,6 @@ using Polygons2d = std::vector; using autoware_perception_msgs::msg::PredictedObjects; using tier4_planning_msgs::msg::PathPointWithLaneId; using tier4_planning_msgs::msg::PathWithLaneId; -using tier4_planning_msgs::msg::StopFactor; -using tier4_planning_msgs::msg::StopReason; namespace planning_utils { @@ -114,10 +111,6 @@ double findReachTime( const double jerk, const double accel, const double velocity, const double distance, const double t_min, const double t_max); -StopReason initializeStopReason(const std::string & stop_reason); - -void appendStopReason(const StopFactor stop_factor, StopReason * stop_reason); - std::vector toRosPoints(const PredictedObjects & object); LineString2d extendLine( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index 2d014d4bbf81d..fb19c4955c12a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -67,8 +67,6 @@ SceneModuleManagerInterface::SceneModuleManagerInterface( std::string("~/virtual_wall/") + module_name, 5); pub_velocity_factor_ = node.create_publisher( std::string("/planning/velocity_factors/") + module_name, 1); - pub_stop_reason_ = - node.create_publisher("~/output/stop_reasons", 1); pub_infrastructure_commands_ = node.create_publisher( "~/output/infrastructure_commands", 1); @@ -107,40 +105,28 @@ void SceneModuleManagerInterface::modifyPathVelocity( StopWatch stop_watch; stop_watch.tic("Total"); visualization_msgs::msg::MarkerArray debug_marker_array; - tier4_planning_msgs::msg::StopReasonArray stop_reason_array; autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array; - stop_reason_array.header.frame_id = "map"; - stop_reason_array.header.stamp = clock_->now(); velocity_factor_array.header.frame_id = "map"; velocity_factor_array.header.stamp = clock_->now(); tier4_v2x_msgs::msg::InfrastructureCommandArray infrastructure_command_array; infrastructure_command_array.stamp = clock_->now(); - first_stop_path_point_distance_ = autoware::motion_utils::calcArcLength(path->points); for (const auto & scene_module : scene_modules_) { - tier4_planning_msgs::msg::StopReason stop_reason; scene_module->resetVelocityFactor(); scene_module->setPlannerData(planner_data_); - scene_module->modifyPathVelocity(path, &stop_reason); + scene_module->modifyPathVelocity(path); // The velocity factor must be called after modifyPathVelocity. const auto velocity_factor = scene_module->getVelocityFactor(); if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { velocity_factor_array.factors.emplace_back(velocity_factor); } - if (stop_reason.reason != "") { - stop_reason_array.stop_reasons.emplace_back(stop_reason); - } if (const auto command = scene_module->getInfrastructureCommand()) { infrastructure_command_array.commands.push_back(*command); } - if (scene_module->getFirstStopPathPointDistance() < first_stop_path_point_distance_) { - first_stop_path_point_distance_ = scene_module->getFirstStopPathPointDistance(); - } - for (const auto & marker : scene_module->createDebugMarkerArray().markers) { debug_marker_array.markers.push_back(marker); } @@ -148,9 +134,6 @@ void SceneModuleManagerInterface::modifyPathVelocity( virtual_wall_marker_creator_.add_virtual_walls(scene_module->createVirtualWalls()); } - if (!stop_reason_array.stop_reasons.empty()) { - pub_stop_reason_->publish(stop_reason_array); - } pub_velocity_factor_->publish(velocity_factor_array); pub_infrastructure_commands_->publish(infrastructure_command_array); pub_debug_->publish(debug_marker_array); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp index ccb2660dbf3c6..88186a5b904b0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp @@ -490,18 +490,6 @@ double calcDecelerationVelocityFromDistanceToTarget( return current_velocity; } -StopReason initializeStopReason(const std::string & stop_reason) -{ - StopReason stop_reason_msg; - stop_reason_msg.reason = stop_reason; - return stop_reason_msg; -} - -void appendStopReason(const StopFactor stop_factor, StopReason * stop_reason) -{ - stop_reason->stop_factors.emplace_back(stop_factor); -} - std::vector toRosPoints(const PredictedObjects & object) { std::vector points; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index c3f91d0506388..32bf81ed63598 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -63,8 +63,7 @@ void RunOutModule::setPlannerParam(const PlannerParam & planner_param) planner_param_ = planner_param; } -bool RunOutModule::modifyPathVelocity( - PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) +bool RunOutModule::modifyPathVelocity(PathWithLaneId * path) { // timer starts const auto t_start = std::chrono::system_clock::now(); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp index 4f326aef298be..3673a215bb749 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -49,7 +49,7 @@ class RunOutModule : public SceneModuleInterface std::unique_ptr dynamic_obstacle_creator, const std::shared_ptr & debug_ptr, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp index dfe5d4de85300..2ac8f1c477620 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp @@ -70,8 +70,7 @@ SpeedBumpModule::SpeedBumpModule( } } -bool SpeedBumpModule::modifyPathVelocity( - PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) +bool SpeedBumpModule::modifyPathVelocity(PathWithLaneId * path) { if (path->points.empty()) { return false; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp index b909dc80689d5..176a01d5112c5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.hpp @@ -56,7 +56,7 @@ class SpeedBumpModule : public SceneModuleInterface const lanelet::autoware::SpeedBump & speed_bump_reg_elem, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index b83a274f99513..8a06b9ba5f82d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -46,7 +46,7 @@ StopLineModule::StopLineModule( velocity_factor_.init(PlanningBehavior::STOP_SIGN); } -bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool StopLineModule::modifyPathVelocity(PathWithLaneId * path) { auto trajectory = trajectory::Trajectory::Builder{}.build( @@ -74,8 +74,6 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop geometry_msgs::msg::Pose stop_pose = trajectory->compute(*stop_point).point.pose; - updateStopReason(stop_reason, stop_pose); - updateDebugData(&debug_data_, stop_pose, state_); return true; @@ -177,15 +175,6 @@ void StopLineModule::updateVelocityFactor( } } -void StopLineModule::updateStopReason( - StopReason * stop_reason, const geometry_msgs::msg::Pose & stop_pose) const -{ - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = stop_pose; - stop_factor.stop_factor_points.push_back(getCenterOfStopLine(stop_line_)); - planning_utils::appendStopReason(stop_factor, stop_reason); -} - void StopLineModule::updateDebugData( DebugData * debug_data, const geometry_msgs::msg::Pose & stop_pose, const State & state) const { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp index cb5bf339f8846..9ac1463da8618 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp @@ -70,7 +70,7 @@ class StopLineModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; /** * @brief Calculate ego position and stop point. @@ -99,8 +99,6 @@ class StopLineModule : public SceneModuleInterface autoware::motion_utils::VelocityFactorInterface * velocity_factor, const State & state, const double & distance_to_stop_point); - void updateStopReason(StopReason * stop_reason, const geometry_msgs::msg::Pose & stop_pose) const; - void updateDebugData( DebugData * debug_data, const geometry_msgs::msg::Pose & stop_pose, const State & state) const; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp index 0394b0c9e381f..3ce8502baaf63 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.cpp @@ -42,8 +42,7 @@ autoware::motion_utils::VirtualWalls TemplateModule::createVirtualWalls() return vw; } -bool TemplateModule::modifyPathVelocity( - [[maybe_unused]] PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason) +bool TemplateModule::modifyPathVelocity([[maybe_unused]] PathWithLaneId * path) { RCLCPP_INFO_ONCE(logger_, "Template Module is executing!"); return false; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp index 9789ee37aa669..70cd5cb1235e7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/src/scene.hpp @@ -38,10 +38,9 @@ class TemplateModule : public SceneModuleInterface * specific criteria. * * @param path A pointer to the path containing points to be modified. - * @param stop_reason A pointer to the stop reason data. * @return [bool] wether the path velocity was modified or not. */ - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; /** * @brief Create a visualization of debug markers. diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp index 0d7c77d5e1b59..b6747724ba6f7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp @@ -57,34 +57,20 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat velocity_factor_array.header.frame_id = "map"; velocity_factor_array.header.stamp = clock_->now(); - tier4_planning_msgs::msg::StopReasonArray stop_reason_array; - stop_reason_array.header.frame_id = "map"; - stop_reason_array.header.stamp = path->header.stamp; - - first_stop_path_point_distance_ = autoware::motion_utils::calcArcLength(path->points); nearest_ref_stop_path_point_index_ = static_cast(path->points.size() - 1); for (const auto & scene_module : scene_modules_) { - tier4_planning_msgs::msg::StopReason stop_reason; std::shared_ptr traffic_light_scene_module( std::dynamic_pointer_cast(scene_module)); traffic_light_scene_module->resetVelocityFactor(); traffic_light_scene_module->setPlannerData(planner_data_); - traffic_light_scene_module->modifyPathVelocity(path, &stop_reason); + traffic_light_scene_module->modifyPathVelocity(path); // The velocity factor must be called after modifyPathVelocity. const auto velocity_factor = traffic_light_scene_module->getVelocityFactor(); if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) { velocity_factor_array.factors.emplace_back(velocity_factor); } - if (stop_reason.reason != "") { - stop_reason_array.stop_reasons.emplace_back(stop_reason); - } - if ( - traffic_light_scene_module->getFirstStopPathPointDistance() < - first_stop_path_point_distance_) { - first_stop_path_point_distance_ = traffic_light_scene_module->getFirstStopPathPointDistance(); - } if ( traffic_light_scene_module->getFirstRefStopPathPointIndex() < nearest_ref_stop_path_point_index_) { @@ -102,9 +88,6 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat virtual_wall_marker_creator_.add_virtual_walls( traffic_light_scene_module->createVirtualWalls()); } - if (!stop_reason_array.stop_reasons.empty()) { - pub_stop_reason_->publish(stop_reason_array); - } pub_velocity_factor_->publish(velocity_factor_array); pub_debug_->publish(debug_marker_array); pub_virtual_wall_->publish(virtual_wall_marker_creator_.create_markers(clock_->now())); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index c59071f2043bb..76f1a19bfc69a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -54,13 +54,11 @@ TrafficLightModule::TrafficLightModule( planner_param_ = planner_param; } -bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path) { debug_data_ = DebugData(); debug_data_.base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; - first_stop_path_point_distance_ = autoware::motion_utils::calcArcLength(path->points); first_ref_stop_path_point_index_ = static_cast(path->points.size()) - 1; - *stop_reason = planning_utils::initializeStopReason(StopReason::TRAFFIC_LIGHT); const auto input_path = *path; @@ -133,8 +131,7 @@ bool TrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * // Decide whether to stop or pass even if a stop signal is received. if (!isPassthrough(signed_arc_length_to_stop_point)) { - *path = - insertStopPose(input_path, stop_line.value().first, stop_line.value().second, stop_reason); + *path = insertStopPose(input_path, stop_line.value().first, stop_line.value().second); is_prev_state_stop_ = true; } return true; @@ -275,7 +272,7 @@ bool TrafficLightModule::isTrafficSignalTimedOut() const tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose( const tier4_planning_msgs::msg::PathWithLaneId & input, const size_t & insert_target_point_idx, - const Eigen::Vector2d & target_point, tier4_planning_msgs::msg::StopReason * stop_reason) + const Eigen::Vector2d & target_point) { tier4_planning_msgs::msg::PathWithLaneId modified_path; modified_path = input; @@ -292,24 +289,9 @@ tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose( size_t insert_index = insert_target_point_idx; planning_utils::insertVelocity(modified_path, target_point_with_lane_id, 0.0, insert_index); - const double target_velocity_point_distance = autoware::motion_utils::calcArcLength(std::vector( - modified_path.points.begin(), modified_path.points.begin() + target_velocity_point_idx)); - if (target_velocity_point_distance < first_stop_path_point_distance_) { - first_stop_path_point_distance_ = target_velocity_point_distance; - debug_data_.first_stop_pose = target_point_with_lane_id.point.pose; - } - - // Get stop point and stop factor - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = debug_data_.first_stop_pose; - if (debug_data_.highest_confidence_traffic_light_point != std::nullopt) { - stop_factor.stop_factor_points = std::vector{ - debug_data_.highest_confidence_traffic_light_point.value()}; - } velocity_factor_.set( modified_path.points, planner_data_->current_odometry->pose, target_point_with_lane_id.point.pose, VelocityFactor::UNKNOWN); - planning_utils::appendStopReason(stop_factor, stop_reason); return modified_path; } diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp index e35d9f86fbe46..8221bb3740273 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.hpp @@ -71,7 +71,7 @@ class TrafficLightModule : public SceneModuleInterface lanelet::ConstLanelet lane, const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; @@ -90,7 +90,7 @@ class TrafficLightModule : public SceneModuleInterface tier4_planning_msgs::msg::PathWithLaneId insertStopPose( const tier4_planning_msgs::msg::PathWithLaneId & input, const size_t & insert_target_point_idx, - const Eigen::Vector2d & target_point, tier4_planning_msgs::msg::StopReason * stop_reason); + const Eigen::Vector2d & target_point); bool isPassthrough(const double & signed_arc_length) const; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp index e60e2a42e3a47..206fb14b6d41c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp @@ -97,11 +97,10 @@ VirtualTrafficLightModule::VirtualTrafficLightModule( logger_ = logger_.get_child((map_data_.instrument_type + "_" + map_data_.instrument_id).c_str()); } -bool VirtualTrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool VirtualTrafficLightModule::modifyPathVelocity(PathWithLaneId * path) { // Initialize setInfrastructureCommand({}); - *stop_reason = planning_utils::initializeStopReason(StopReason::VIRTUAL_TRAFFIC_LIGHT); module_data_ = {}; @@ -150,7 +149,7 @@ bool VirtualTrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopRe // Stop at stop_line if no message received if (!virtual_traffic_light_state) { RCLCPP_DEBUG(logger_, "no message received"); - insertStopVelocityAtStopLine(path, stop_reason, end_line_idx); + insertStopVelocityAtStopLine(path, end_line_idx); updateInfrastructureCommand(); return true; } @@ -158,7 +157,7 @@ bool VirtualTrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopRe // Stop at stop_line if no right is given if (!hasRightOfWay(*virtual_traffic_light_state)) { RCLCPP_DEBUG(logger_, "no right is given"); - insertStopVelocityAtStopLine(path, stop_reason, end_line_idx); + insertStopVelocityAtStopLine(path, end_line_idx); updateInfrastructureCommand(); return true; } @@ -167,7 +166,7 @@ bool VirtualTrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopRe if (isBeforeStopLine(end_line_idx)) { if (isStateTimeout(*virtual_traffic_light_state)) { RCLCPP_DEBUG(logger_, "state is timeout before stop line"); - insertStopVelocityAtStopLine(path, stop_reason, end_line_idx); + insertStopVelocityAtStopLine(path, end_line_idx); } updateInfrastructureCommand(); @@ -181,7 +180,7 @@ bool VirtualTrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopRe if ( planner_param_.check_timeout_after_stop_line && isStateTimeout(*virtual_traffic_light_state)) { RCLCPP_DEBUG(logger_, "state is timeout after stop line"); - insertStopVelocityAtStopLine(path, stop_reason, end_line_idx); + insertStopVelocityAtStopLine(path, end_line_idx); updateInfrastructureCommand(); return true; } @@ -189,7 +188,7 @@ bool VirtualTrafficLightModule::modifyPathVelocity(PathWithLaneId * path, StopRe // Stop at stop_line if finalization isn't completed if (!virtual_traffic_light_state->is_finalized) { RCLCPP_DEBUG(logger_, "finalization isn't completed"); - insertStopVelocityAtEndLine(path, stop_reason, end_line_idx); + insertStopVelocityAtEndLine(path, end_line_idx); if (isNearAnyEndLine(end_line_idx) && planner_data_->isVehicleStopped()) { state_ = State::FINALIZING; @@ -207,15 +206,6 @@ void VirtualTrafficLightModule::updateInfrastructureCommand() setInfrastructureCommand(command_); } -void VirtualTrafficLightModule::setStopReason( - const geometry_msgs::msg::Pose & stop_pose, tier4_planning_msgs::msg::StopReason * stop_reason) -{ - tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = stop_pose; - stop_factor.stop_factor_points.push_back(toMsg(map_data_.instrument_center)); - planning_utils::appendStopReason(stop_factor, stop_reason); -} - std::optional VirtualTrafficLightModule::getPathIndexOfFirstEndLine() { std::optional min_seg_idx; @@ -376,8 +366,7 @@ bool VirtualTrafficLightModule::hasRightOfWay( } void VirtualTrafficLightModule::insertStopVelocityAtStopLine( - tier4_planning_msgs::msg::PathWithLaneId * path, - tier4_planning_msgs::msg::StopReason * stop_reason, const size_t end_line_idx) + tier4_planning_msgs::msg::PathWithLaneId * path, const size_t end_line_idx) { const auto collision = findLastCollisionBeforeEndLine(path->points, *map_data_.stop_line, end_line_idx); @@ -428,7 +417,6 @@ void VirtualTrafficLightModule::insertStopVelocityAtStopLine( } // Set StopReason - setStopReason(stop_pose, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN, command_.type); @@ -439,8 +427,7 @@ void VirtualTrafficLightModule::insertStopVelocityAtStopLine( } void VirtualTrafficLightModule::insertStopVelocityAtEndLine( - tier4_planning_msgs::msg::PathWithLaneId * path, - tier4_planning_msgs::msg::StopReason * stop_reason, const size_t end_line_idx) + tier4_planning_msgs::msg::PathWithLaneId * path, const size_t end_line_idx) { const auto collision = findLastCollisionBeforeEndLine(path->points, map_data_.end_lines, end_line_idx); @@ -463,7 +450,6 @@ void VirtualTrafficLightModule::insertStopVelocityAtEndLine( } // Set StopReason - setStopReason(stop_pose, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp index e4e58e4288354..b031ba5b2bb2b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp @@ -79,7 +79,7 @@ class VirtualTrafficLightModule : public SceneModuleInterface const PlannerParam & planner_param, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; @@ -96,8 +96,6 @@ class VirtualTrafficLightModule : public SceneModuleInterface void updateInfrastructureCommand(); - void setStopReason(const Pose & stop_pose, StopReason * stop_reason); - void setVelocityFactor( const geometry_msgs::msg::Pose & stop_pose, autoware_adapi_v1_msgs::msg::VelocityFactor * velocity_factor); @@ -119,12 +117,10 @@ class VirtualTrafficLightModule : public SceneModuleInterface bool hasRightOfWay(const tier4_v2x_msgs::msg::VirtualTrafficLightState & state); void insertStopVelocityAtStopLine( - tier4_planning_msgs::msg::PathWithLaneId * path, - tier4_planning_msgs::msg::StopReason * stop_reason, const size_t end_line_idx); + tier4_planning_msgs::msg::PathWithLaneId * path, const size_t end_line_idx); void insertStopVelocityAtEndLine( - tier4_planning_msgs::msg::PathWithLaneId * path, - tier4_planning_msgs::msg::StopReason * stop_reason, const size_t end_line_idx); + tier4_planning_msgs::msg::PathWithLaneId * path, const size_t end_line_idx); }; } // namespace autoware::behavior_velocity_planner #endif // SCENE_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp index 765732969951d..42a235a67edd1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp @@ -81,12 +81,11 @@ std::pair WalkwayModule::getStopLine( return std::make_pair(dist_ego_to_stop, p_stop_line); } -bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) +bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path) { const auto & base_link2front = planner_data_->vehicle_info_.max_longitudinal_offset_m; debug_data_ = DebugData(planner_data_); - *stop_reason = planning_utils::initializeStopReason(StopReason::WALKWAY); const auto input = *path; @@ -119,10 +118,6 @@ bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_ } /* get stop point and stop factor */ - StopFactor stop_factor; - stop_factor.stop_pose = stop_pose.value(); - stop_factor.stop_factor_points.push_back(path_end_points_on_walkway->first); - planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose.value(), VelocityFactor::UNKNOWN); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp index a400f57451d2e..df54eafd11cc2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.hpp @@ -46,7 +46,7 @@ class WalkwayModule : public SceneModuleInterface const PlannerParam & planner_param, const bool use_regulatory_element, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock); - bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override; + bool modifyPathVelocity(PathWithLaneId * path) override; visualization_msgs::msg::MarkerArray createDebugMarkerArray() override; autoware::motion_utils::VirtualWalls createVirtualWalls() override; From b5c98ef5703764936426a7d91da307200c408e60 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Mon, 2 Dec 2024 20:18:03 +0900 Subject: [PATCH 196/273] refactor(autoware_behavior_path_side_shift_module): refactor shift length retrieval and improve path orientation handling (#9539) refactor(side_shift_module): refactor shift length retrieval and improve path orientation handling Signed-off-by: Kyoichi Sugahara --- .../behavior_path_side_shift_module/scene.hpp | 2 -- .../behavior_path_side_shift_module/utils.hpp | 19 ++++++++++++- .../src/scene.cpp | 28 ++++++++----------- .../src/utils.cpp | 17 +++++------ 4 files changed, 38 insertions(+), 28 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp index 543b17aca9352..15d81ff45abcf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/scene.hpp @@ -87,8 +87,6 @@ class SideShiftModule : public SceneModuleInterface // const methods void publishPath(const PathWithLaneId & path) const; - double getClosestShiftLength() const; - // member PathWithLaneId refined_path_{}; PathWithLaneId reference_path_{}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp index d5888ab6a79d1..5a3e51c353c39 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/include/autoware/behavior_path_side_shift_module/utils.hpp @@ -15,6 +15,8 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ #define AUTOWARE__BEHAVIOR_PATH_SIDE_SHIFT_MODULE__UTILS_HPP_ +#include "autoware/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" + #include #include #include @@ -27,9 +29,24 @@ using geometry_msgs::msg::Pose; using geometry_msgs::msg::TransformStamped; using tier4_planning_msgs::msg::PathWithLaneId; +/** + * @brief Sets the orientation (yaw angle) for all points in the path. + * @param [in,out] path Path with lane ID to set orientation. + * @details For each point, calculates orientation based on: + * - Vector to next point if not last point + * - Vector from previous point if last point + * - Zero angle if single point + */ void setOrientation(PathWithLaneId * path); -bool isAlmostZero(double v); +/** + * @brief Gets the shift length at the closest path point to the ego position. + * @param [in] shifted_path Path with shift length information. + * @param [in] ego_point Current ego position. + * @return Shift length at the closest path point. Returns 0.0 if path is empty. + */ +double getClosestShiftLength( + const ShiftedPath & shifted_path, const geometry_msgs::msg::Point ego_point); } // namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index 5970a3a807517..d855f1cdcde24 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -88,8 +88,7 @@ bool SideShiftModule::isExecutionRequested() const } // If the desired offset has a non-zero value, return true as we want to execute the plan. - - const bool has_request = !isAlmostZero(requested_lateral_offset_); + const bool has_request = std::fabs(requested_lateral_offset_) >= 1.0e-4; RCLCPP_DEBUG_STREAM( getLogger(), "ESS::isExecutionRequested() : " << std::boolalpha << has_request); @@ -119,6 +118,7 @@ bool SideShiftModule::canTransitSuccessState() { // Never return the FAILURE. When the desired offset is zero and the vehicle is in the original // drivable area,this module can stop the computation and return SUCCESS. + constexpr double ZERO_THRESHOLD = 1.0e-4; const auto isOffsetDiffAlmostZero = [this]() noexcept { const auto last_sp = path_shifter_.getLastShiftLine(); @@ -126,7 +126,7 @@ bool SideShiftModule::canTransitSuccessState() const auto length = std::fabs(last_sp.value().end_shift_length); const auto lateral_offset = std::fabs(requested_lateral_offset_); const auto offset_diff = lateral_offset - length; - if (!isAlmostZero(offset_diff)) { + if (std::fabs(offset_diff) >= ZERO_THRESHOLD) { lateral_offset_change_request_ = true; return false; } @@ -135,7 +135,7 @@ bool SideShiftModule::canTransitSuccessState() }(); const bool no_offset_diff = isOffsetDiffAlmostZero; - const bool no_request = isAlmostZero(requested_lateral_offset_); + const bool no_request = std::fabs(requested_lateral_offset_) < ZERO_THRESHOLD; const auto no_shifted_plan = [&]() { if (prev_output_.shift_length.empty()) { @@ -279,6 +279,11 @@ BehaviorModuleOutput SideShiftModule::plan() ShiftedPath shifted_path; path_shifter_.generate(&shifted_path); + if (shifted_path.path.points.empty()) { + RCLCPP_ERROR(getLogger(), "Generated shift_path has no points"); + return {}; + } + // Reset orientation setOrientation(&shifted_path.path); @@ -345,7 +350,8 @@ ShiftLine SideShiftModule::calcShiftLine() const std::max(p->min_distance_to_start_shifting, ego_speed * p->time_to_start_shifting); const double dist_to_end = [&]() { - const double shift_length = requested_lateral_offset_ - getClosestShiftLength(); + const double shift_length = + requested_lateral_offset_ - getClosestShiftLength(prev_output_, getEgoPose().position); const double jerk_shifting_distance = autoware::motion_utils::calc_longitudinal_dist_from_jerk( shift_length, p->shifting_lateral_jerk, std::max(ego_speed, p->min_shifting_speed)); const double shifting_distance = std::max(jerk_shifting_distance, p->min_shifting_distance); @@ -367,18 +373,6 @@ ShiftLine SideShiftModule::calcShiftLine() const return shift_line; } -double SideShiftModule::getClosestShiftLength() const -{ - if (prev_output_.shift_length.empty()) { - return 0.0; - } - - const auto ego_point = planner_data_->self_odometry->pose.pose.position; - const auto closest = - autoware::motion_utils::findNearestIndex(prev_output_.path.points, ego_point); - return prev_output_.shift_length.at(closest); -} - BehaviorModuleOutput SideShiftModule::adjustDrivableArea(const ShiftedPath & path) const { BehaviorModuleOutput out; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp index f30895c10d64d..942e87f57d05e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/utils.cpp @@ -26,12 +26,6 @@ namespace autoware::behavior_path_planner { void setOrientation(PathWithLaneId * path) { - if (!path) { - RCLCPP_ERROR( - rclcpp::get_logger("behavior_path_planner").get_child("side_shift").get_child("util"), - "Pointer to path is NULL!"); - } - // Reset orientation for (size_t idx = 0; idx < path->points.size(); ++idx) { double angle = 0.0; @@ -53,9 +47,16 @@ void setOrientation(PathWithLaneId * path) } } -bool isAlmostZero(double v) +double getClosestShiftLength( + const ShiftedPath & shifted_path, const geometry_msgs::msg::Point ego_point) { - return std::fabs(v) < 1.0e-4; + if (shifted_path.shift_length.empty()) { + return 0.0; + } + + const auto closest = + autoware::motion_utils::findNearestIndex(shifted_path.path.points, ego_point); + return shifted_path.shift_length.at(closest); } } // namespace autoware::behavior_path_planner From 2de47657c6f0f990f1e8e8112973963e836f9bfb Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Tue, 3 Dec 2024 00:34:10 +0900 Subject: [PATCH 197/273] fix(autoware_bytetrack): update visualizer param path and not to set default value (#9490) fix: update visualizer param path and not to set default value Signed-off-by: ktro2828 --- perception/autoware_bytetrack/launch/bytetrack.launch.xml | 2 +- perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_bytetrack/launch/bytetrack.launch.xml b/perception/autoware_bytetrack/launch/bytetrack.launch.xml index ace84d4799a8a..c009ed93754fa 100644 --- a/perception/autoware_bytetrack/launch/bytetrack.launch.xml +++ b/perception/autoware_bytetrack/launch/bytetrack.launch.xml @@ -5,7 +5,7 @@ - + diff --git a/perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp b/perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp index 4276b86f5cab7..97cee4f67ccb9 100644 --- a/perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp +++ b/perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp @@ -34,7 +34,7 @@ ByteTrackVisualizerNode::ByteTrackVisualizerNode(const rclcpp::NodeOptions & nod { using std::chrono_literals::operator""ms; - use_raw_ = declare_parameter("use_raw", false); + use_raw_ = declare_parameter("use_raw"); // Create timer to find proper settings for subscribed topics timer_ = rclcpp::create_timer( From 214c9b7834c79888cfbc711368d4a984f865a491 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Tue, 3 Dec 2024 00:49:09 +0900 Subject: [PATCH 198/273] refactor(perception_online_evaluator): use tier4_metric_msgs instead of diagnostic_msgs (#9485) --- .../perception_online_evaluator/README.md | 10 +-- .../perception_online_evaluator_node.hpp | 34 ++++++--- .../perception_online_evaluator/package.xml | 2 +- .../src/perception_online_evaluator_node.cpp | 72 +++++++++---------- .../test_perception_online_evaluator_node.cpp | 42 +++++------ 5 files changed, 83 insertions(+), 77 deletions(-) diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/perception_online_evaluator/README.md index 7df375ac236d0..17e7e1a2b5652 100644 --- a/evaluator/perception_online_evaluator/README.md +++ b/evaluator/perception_online_evaluator/README.md @@ -155,11 +155,11 @@ where: ## Inputs / Outputs -| Name | Type | Description | -| ----------------- | ------------------------------------------------- | ------------------------------------------------- | -| `~/input/objects` | `autoware_perception_msgs::msg::PredictedObjects` | The predicted objects to evaluate. | -| `~/metrics` | `diagnostic_msgs::msg::DiagnosticArray` | Diagnostic information about perception accuracy. | -| `~/markers` | `visualization_msgs::msg::MarkerArray` | Visual markers for debugging and visualization. | +| Name | Type | Description | +| ----------------- | ------------------------------------------------- | ----------------------------------------------- | +| `~/input/objects` | `autoware_perception_msgs::msg::PredictedObjects` | The predicted objects to evaluate. | +| `~/metrics` | `tier4_metric_msgs::msg::MetricArray` | Metric information about perception accuracy. | +| `~/markers` | `visualization_msgs::msg::MarkerArray` | Visual markers for debugging and visualization. | ## Parameters diff --git a/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp b/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp index ea560a48f928b..61c1ba40134df 100644 --- a/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp +++ b/evaluator/perception_online_evaluator/include/perception_online_evaluator/perception_online_evaluator_node.hpp @@ -23,9 +23,10 @@ #include "tf2_ros/transform_listener.h" #include "autoware_perception_msgs/msg/predicted_objects.hpp" -#include "diagnostic_msgs/msg/diagnostic_array.hpp" #include "nav_msgs/msg/odometry.hpp" #include "visualization_msgs/msg/marker_array.hpp" +#include +#include #include #include @@ -38,8 +39,6 @@ namespace perception_diagnostics using autoware::universe_utils::Accumulator; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; -using diagnostic_msgs::msg::DiagnosticArray; -using diagnostic_msgs::msg::DiagnosticStatus; using nav_msgs::msg::Odometry; using TFMessage = tf2_msgs::msg::TFMessage; @@ -60,15 +59,34 @@ class PerceptionOnlineEvaluatorNode : public rclcpp::Node */ void onObjects(const PredictedObjects::ConstSharedPtr objects_msg); - DiagnosticStatus generateDiagnosticStatus( - const std::string metric, const Accumulator & metric_stat) const; - DiagnosticStatus generateDiagnosticStatus( - const std::string & metric, const double metric_value) const; + /** + * @brief Convert metric statistic to `tier4_metric_msgs::msg::Metric` and append to + * `tier4_metric_msgs::msg::MetricArray`. + * + * @param metric Metric name. + * @param metric_stat Metric statistic. + * @param metrics_msg Metrics value container. + */ + void toMetricMsg( + const std::string & metric, const Accumulator & metric_stat, + tier4_metric_msgs::msg::MetricArray & metrics_msg) const; + + /** + * @brief Convert metric value to `tier4_metric_msgs::msg::Metric` and append to + * `tier4_metric_msgs::msg::MetricArray + * + * @param metric Metric name. + * @param metric_stat Metric value. + * @param metrics_msg Metrics value container. + */ + void toMetricMsg( + const std::string & metric, const double metric_value, + tier4_metric_msgs::msg::MetricArray & metrics_msg) const; private: // Subscribers and publishers rclcpp::Subscription::SharedPtr objects_sub_; - rclcpp::Publisher::SharedPtr metrics_pub_; + rclcpp::Publisher::SharedPtr metrics_pub_; rclcpp::Publisher::SharedPtr pub_marker_; // TF diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/perception_online_evaluator/package.xml index 654586a76453d..1e7c0a7d128e6 100644 --- a/evaluator/perception_online_evaluator/package.xml +++ b/evaluator/perception_online_evaluator/package.xml @@ -23,7 +23,6 @@ autoware_perception_msgs autoware_universe_utils autoware_vehicle_info_utils - diagnostic_msgs eigen geometry_msgs glog @@ -33,6 +32,7 @@ rclcpp_components tf2 tf2_ros + tier4_metric_msgs ament_cmake_ros ament_index_cpp diff --git a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp index abbdbd382498a..7d8344c24819c 100644 --- a/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/src/perception_online_evaluator_node.cpp @@ -50,7 +50,7 @@ PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode( objects_sub_ = create_subscription( "~/input/objects", 1, std::bind(&PerceptionOnlineEvaluatorNode::onObjects, this, _1)); - metrics_pub_ = create_publisher("~/metrics", 1); + metrics_pub_ = create_publisher("~/metrics", 1); pub_marker_ = create_publisher("~/markers", 10); tf_buffer_ = std::make_unique(this->get_clock()); @@ -65,7 +65,8 @@ PerceptionOnlineEvaluatorNode::PerceptionOnlineEvaluatorNode( void PerceptionOnlineEvaluatorNode::publishMetrics() { - DiagnosticArray metrics_msg; + // DiagnosticArray metrics_msg; + tier4_metric_msgs::msg::MetricArray metrics_msg; // calculate metrics for (const Metric & metric : parameters_->metrics) { @@ -80,10 +81,10 @@ void PerceptionOnlineEvaluatorNode::publishMetrics() for (const auto & [metric, value] : arg) { if constexpr (std::is_same_v) { if (value.count() > 0) { - metrics_msg.status.emplace_back(generateDiagnosticStatus(metric, value)); + toMetricMsg(metric, value, metrics_msg); } } else if constexpr (std::is_same_v) { - metrics_msg.status.emplace_back(generateDiagnosticStatus(metric, value)); + toMetricMsg(metric, value, metrics_msg); } } }, @@ -91,49 +92,44 @@ void PerceptionOnlineEvaluatorNode::publishMetrics() } // publish metrics - if (!metrics_msg.status.empty()) { - metrics_msg.header.stamp = now(); + if (!metrics_msg.metric_array.empty()) { + metrics_msg.stamp = now(); metrics_pub_->publish(metrics_msg); } publishDebugMarker(); } -DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus( - const std::string metric, const Accumulator & metric_stat) const +void PerceptionOnlineEvaluatorNode::toMetricMsg( + const std::string & metric, const Accumulator & metric_stat, + tier4_metric_msgs::msg::MetricArray & metrics_msg) const { - DiagnosticStatus status; - - status.level = status.OK; - status.name = metric; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "min"; - key_value.value = std::to_string(metric_stat.min()); - status.values.push_back(key_value); - key_value.key = "max"; - key_value.value = std::to_string(metric_stat.max()); - status.values.push_back(key_value); - key_value.key = "mean"; - key_value.value = std::to_string(metric_stat.mean()); - status.values.push_back(key_value); - - return status; + // min value + metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build() + .name(metric + "/min") + .unit("") + .value(std::to_string(metric_stat.min()))); + + // max value + metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build() + .name(metric + "/max") + .unit("") + .value(std::to_string(metric_stat.max()))); + + // mean value + metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build() + .name(metric + "/mean") + .unit("") + .value(std::to_string(metric_stat.mean()))); } -DiagnosticStatus PerceptionOnlineEvaluatorNode::generateDiagnosticStatus( - const std::string & metric, const double value) const +void PerceptionOnlineEvaluatorNode::toMetricMsg( + const std::string & metric, const double metric_value, + tier4_metric_msgs::msg::MetricArray & metrics_msg) const { - DiagnosticStatus status; - - status.level = status.OK; - status.name = metric; - - diagnostic_msgs::msg::KeyValue key_value; - key_value.key = "metric_value"; - key_value.value = std::to_string(value); - status.values.push_back(key_value); - - return status; + metrics_msg.metric_array.emplace_back(tier4_metric_msgs::build() + .name(metric + "/metric_value") + .unit("") + .value(std::to_string(metric_value))); } void PerceptionOnlineEvaluatorNode::onObjects(const PredictedObjects::ConstSharedPtr objects_msg) diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index e2ab22be2b61b..5b23f6d37a1d4 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -21,7 +21,7 @@ #include #include -#include +#include #include #include "boost/lexical_cast.hpp" @@ -37,7 +37,6 @@ using EvalNode = perception_diagnostics::PerceptionOnlineEvaluatorNode; using PredictedObjects = autoware_perception_msgs::msg::PredictedObjects; using PredictedObject = autoware_perception_msgs::msg::PredictedObject; -using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray; using MarkerArray = visualization_msgs::msg::MarkerArray; using ObjectClassification = autoware_perception_msgs::msg::ObjectClassification; using nav_msgs::msg::Odometry; @@ -125,36 +124,29 @@ class EvalTest : public ::testing::Test tf_pub_->publish(tf_msg); } - void setTargetMetric(perception_diagnostics::Metric metric) + void setTargetMetric(const perception_diagnostics::Metric & metric) { const auto metric_str = perception_diagnostics::metric_to_str.at(metric); setTargetMetric(metric_str); } - void setTargetMetric(std::string metric_str) + void setTargetMetric(const std::string & metric_str) { - const auto is_target_metric = [metric_str](const auto & status) { - return status.name == metric_str; - }; - metric_sub_ = rclcpp::create_subscription( + metric_sub_ = rclcpp::create_subscription( eval_node, "/perception_online_evaluator/metrics", 1, - [=](const DiagnosticArray::ConstSharedPtr msg) { - const auto it = std::find_if(msg->status.begin(), msg->status.end(), is_target_metric); - if (it != msg->status.end()) { - const auto mean_it = std::find_if( - it->values.begin(), it->values.end(), - [](const auto & key_value) { return key_value.key == "mean"; }); - if (mean_it != it->values.end()) { - metric_value_ = boost::lexical_cast(mean_it->value); - } else { - const auto metric_value_it = std::find_if( - it->values.begin(), it->values.end(), - [](const auto & key_value) { return key_value.key == "metric_value"; }); - if (metric_value_it != it->values.end()) { - metric_value_ = boost::lexical_cast(metric_value_it->value); - } - } + [this, metric_str](const tier4_metric_msgs::msg::MetricArray::ConstSharedPtr msg) { + // extract a metric whose name includes metrics_str + const auto it = std::find_if( + msg->metric_array.begin(), msg->metric_array.end(), [&metric_str](const auto & metric) { + return metric.name == metric_str + "/metric_value" || + metric.name == metric_str + "/mean"; + }); + + if (it != msg->metric_array.end()) { + metric_value_ = boost::lexical_cast(it->value); metric_updated_ = true; + } else { + metric_updated_ = false; } }); } @@ -316,7 +308,7 @@ class EvalTest : public ::testing::Test // Pub/Sub rclcpp::Publisher::SharedPtr objects_pub_; - rclcpp::Subscription::SharedPtr metric_sub_; + rclcpp::Subscription::SharedPtr metric_sub_; rclcpp::Subscription::SharedPtr marker_sub_; rclcpp::Publisher::SharedPtr tf_pub_; bool has_received_marker_{false}; From 78ceed76908a51c511b398a3397f452404cfffce Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 3 Dec 2024 11:40:13 +0900 Subject: [PATCH 199/273] refactor(test_utils): return parser as optional (#9391) Signed-off-by: Zulfaqar Azmi Co-authored-by: Mamoru Sobue --- .../autoware_test_utils/mock_data_parser.hpp | 5 +- .../src/autoware_test_utils.cpp | 7 +- .../src/mock_data_parser.cpp | 45 +++--- .../test/test_mock_data_parser.cpp | 140 ++++++++++-------- .../src/autoware_planning_test_manager.cpp | 23 ++- .../test/test_route_handler.hpp | 15 +- .../test/test_lane_change_scene.cpp | 6 +- 7 files changed, 135 insertions(+), 106 deletions(-) diff --git a/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp index 5d36e8aefef3b..5e07237e2c495 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp @@ -35,6 +35,7 @@ #include #include +#include #include #include #include @@ -197,10 +198,10 @@ template T parse(const std::string & filename); template <> -LaneletRoute parse(const std::string & filename); +std::optional parse(const std::string & filename); template <> -PathWithLaneId parse(const std::string & filename); +std::optional parse(const std::string & filename); template auto create_const_shared_ptr(MessageType && payload) diff --git a/common/autoware_test_utils/src/autoware_test_utils.cpp b/common/autoware_test_utils/src/autoware_test_utils.cpp index 696f58d5e19e8..d61dc61c81e65 100644 --- a/common/autoware_test_utils/src/autoware_test_utils.cpp +++ b/common/autoware_test_utils/src/autoware_test_utils.cpp @@ -310,7 +310,12 @@ PathWithLaneId loadPathWithLaneIdInYaml() const auto yaml_path = get_absolute_path_to_config("autoware_test_utils", "path_with_lane_id_data.yaml"); - return parse(yaml_path); + if (const auto path = parse>(yaml_path)) { + return *path; + } + + throw std::runtime_error( + "Failed to parse YAML file: " + yaml_path + ". The file might be corrupted."); } lanelet::ConstLanelet make_lanelet( diff --git a/common/autoware_test_utils/src/mock_data_parser.cpp b/common/autoware_test_utils/src/mock_data_parser.cpp index 9e895c7b4027d..6e7002501bf30 100644 --- a/common/autoware_test_utils/src/mock_data_parser.cpp +++ b/common/autoware_test_utils/src/mock_data_parser.cpp @@ -17,6 +17,7 @@ #include #include +#include #include #include @@ -220,11 +221,7 @@ std::vector parse>(const Y { std::vector path_points; - if (!node["points"]) { - return path_points; - } - - const auto & points = node["points"]; + const auto & points = node; path_points.reserve(points.size()); std::transform( points.begin(), points.end(), std::back_inserter(path_points), [&](const YAML::Node & input) { @@ -428,36 +425,30 @@ OperationModeState parse(const YAML::Node & node) } template <> -LaneletRoute parse(const std::string & filename) +std::optional parse(const std::string & filename) { - LaneletRoute lanelet_route; - try { - YAML::Node config = YAML::LoadFile(filename); - - lanelet_route.start_pose = (config["start_pose"]) ? parse(config["start_pose"]) : Pose(); - lanelet_route.goal_pose = (config["goal_pose"]) ? parse(config["goal_pose"]) : Pose(); - lanelet_route.segments = parse>(config["segments"]); - } catch (const std::exception & e) { - RCLCPP_DEBUG(rclcpp::get_logger("autoware_test_utils"), "Exception caught: %s", e.what()); + YAML::Node node = YAML::LoadFile(filename); + if (!node["start_pose"] || !node["goal_pose"] || !node["segments"]) { + return std::nullopt; } - return lanelet_route; + + return parse(node); } template <> -PathWithLaneId parse(const std::string & filename) +std::optional parse(const std::string & filename) { - PathWithLaneId path; - YAML::Node yaml_node = YAML::LoadFile(filename); - - try { - path.header = parse
(yaml_node["header"]); - path.points = parse>(yaml_node); - path.left_bound = parse>(yaml_node["left_bound"]); - path.right_bound = parse>(yaml_node["right_bound"]); - } catch (const std::exception & e) { - RCLCPP_DEBUG(rclcpp::get_logger("autoware_test_utils"), "Exception caught: %s", e.what()); + YAML::Node node = YAML::LoadFile(filename); + + if (!node["header"] || !node["points"] || !node["left_bound"] || !node["right_bound"]) { + return std::nullopt; } + PathWithLaneId path; + path.header = parse
(node["header"]); + path.points = parse>(node["points"]); + path.left_bound = parse>(node["left_bound"]); + path.right_bound = parse>(node["right_bound"]); return path; } } // namespace autoware::test_utils diff --git a/common/autoware_test_utils/test/test_mock_data_parser.cpp b/common/autoware_test_utils/test/test_mock_data_parser.cpp index a0dd0fce9bd29..f2b23cc43b07b 100644 --- a/common/autoware_test_utils/test/test_mock_data_parser.cpp +++ b/common/autoware_test_utils/test/test_mock_data_parser.cpp @@ -788,38 +788,44 @@ TEST(ParseFunction, CompleteFromFilename) const auto parser_test_route = autoware_test_utils_dir + "/test_data/lanelet_route_parser_test.yaml"; - const auto lanelet_route = parse(parser_test_route); - EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.x, 1.0); - EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.y, 2.0); - EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.z, 3.0); + if (const auto lanelet_route_opt = parse>(parser_test_route)) { + const auto & lanelet_route = *lanelet_route_opt; + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.x, 1.0); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.y, 2.0); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.position.z, 3.0); - EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.x, 0.1); - EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.y, 0.2); - EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.z, 0.3); - EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.w, 0.4); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.x, 0.1); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.y, 0.2); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.z, 0.3); + EXPECT_DOUBLE_EQ(lanelet_route.start_pose.orientation.w, 0.4); - EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.x, 4.0); - EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.y, 5.0); - EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.z, 6.0); - EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.x, 0.5); - EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.y, 0.6); - EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.z, 0.7); - EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.w, 0.8); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.x, 4.0); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.y, 5.0); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.position.z, 6.0); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.x, 0.5); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.y, 0.6); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.z, 0.7); + EXPECT_DOUBLE_EQ(lanelet_route.goal_pose.orientation.w, 0.8); - ASSERT_EQ( - lanelet_route.segments.size(), - uint64_t(2)); // Assuming only one segment in the provided YAML for this test - const auto & segment1 = lanelet_route.segments[1]; - EXPECT_EQ(segment1.preferred_primitive.id, 44); - EXPECT_EQ(segment1.primitives.size(), uint64_t(4)); - EXPECT_EQ(segment1.primitives[0].id, 55); - EXPECT_EQ(segment1.primitives[0].primitive_type, "lane"); - EXPECT_EQ(segment1.primitives[1].id, 66); - EXPECT_EQ(segment1.primitives[1].primitive_type, "lane"); - EXPECT_EQ(segment1.primitives[2].id, 77); - EXPECT_EQ(segment1.primitives[2].primitive_type, "lane"); - EXPECT_EQ(segment1.primitives[3].id, 88); - EXPECT_EQ(segment1.primitives[3].primitive_type, "lane"); + ASSERT_EQ( + lanelet_route.segments.size(), + uint64_t(2)); // Assuming only one segment in the provided YAML for this test + const auto & segment1 = lanelet_route.segments[1]; + EXPECT_EQ(segment1.preferred_primitive.id, 44); + EXPECT_EQ(segment1.primitives.size(), uint64_t(4)); + EXPECT_EQ(segment1.primitives[0].id, 55); + EXPECT_EQ(segment1.primitives[0].primitive_type, "lane"); + EXPECT_EQ(segment1.primitives[1].id, 66); + EXPECT_EQ(segment1.primitives[1].primitive_type, "lane"); + EXPECT_EQ(segment1.primitives[2].id, 77); + EXPECT_EQ(segment1.primitives[2].primitive_type, "lane"); + EXPECT_EQ(segment1.primitives[3].id, 88); + EXPECT_EQ(segment1.primitives[3].primitive_type, "lane"); + } else { + const std::string fail_reason = + "Failed to parse YAML file: " + parser_test_route + ". The file might be corrupted."; + FAIL() << fail_reason; + } } TEST(ParseFunction, ParsePathWithLaneID) @@ -829,45 +835,49 @@ TEST(ParseFunction, ParsePathWithLaneID) const auto parser_test_path = autoware_test_utils_dir + "/test_data/path_with_lane_id_parser_test.yaml"; - const auto path = parse(parser_test_path); - EXPECT_EQ(path.header.stamp.sec, 20); - EXPECT_EQ(path.header.stamp.nanosec, 5); + if (const auto path_opt = parse>(parser_test_path)) { + const auto & path = *path_opt; + EXPECT_EQ(path.header.stamp.sec, 20); + EXPECT_EQ(path.header.stamp.nanosec, 5); - const auto path_points = path.points; - const auto & p1 = path_points.front(); - EXPECT_DOUBLE_EQ(p1.point.pose.position.x, 12.9); - EXPECT_DOUBLE_EQ(p1.point.pose.position.y, 3.8); - EXPECT_DOUBLE_EQ(p1.point.pose.position.z, 4.7); - EXPECT_DOUBLE_EQ(p1.point.pose.orientation.x, 1.0); - EXPECT_DOUBLE_EQ(p1.point.pose.orientation.y, 2.0); - EXPECT_DOUBLE_EQ(p1.point.pose.orientation.z, 3.0); - EXPECT_DOUBLE_EQ(p1.point.pose.orientation.w, 4.0); - EXPECT_FLOAT_EQ(p1.point.longitudinal_velocity_mps, 1.2); - EXPECT_FLOAT_EQ(p1.point.lateral_velocity_mps, 3.4); - EXPECT_FLOAT_EQ(p1.point.heading_rate_rps, 5.6); - EXPECT_TRUE(p1.point.is_final); - EXPECT_EQ(p1.lane_ids.front(), 912); + const auto path_points = path.points; + const auto & p1 = path_points.front(); + EXPECT_DOUBLE_EQ(p1.point.pose.position.x, 12.9); + EXPECT_DOUBLE_EQ(p1.point.pose.position.y, 3.8); + EXPECT_DOUBLE_EQ(p1.point.pose.position.z, 4.7); + EXPECT_DOUBLE_EQ(p1.point.pose.orientation.x, 1.0); + EXPECT_DOUBLE_EQ(p1.point.pose.orientation.y, 2.0); + EXPECT_DOUBLE_EQ(p1.point.pose.orientation.z, 3.0); + EXPECT_DOUBLE_EQ(p1.point.pose.orientation.w, 4.0); + EXPECT_FLOAT_EQ(p1.point.longitudinal_velocity_mps, 1.2); + EXPECT_FLOAT_EQ(p1.point.lateral_velocity_mps, 3.4); + EXPECT_FLOAT_EQ(p1.point.heading_rate_rps, 5.6); + EXPECT_TRUE(p1.point.is_final); + EXPECT_EQ(p1.lane_ids.front(), 912); - const auto & p2 = path_points.back(); - EXPECT_DOUBLE_EQ(p2.point.pose.position.x, 0.0); - EXPECT_DOUBLE_EQ(p2.point.pose.position.y, 20.5); - EXPECT_DOUBLE_EQ(p2.point.pose.position.z, 90.11); - EXPECT_DOUBLE_EQ(p2.point.pose.orientation.x, 4.0); - EXPECT_DOUBLE_EQ(p2.point.pose.orientation.y, 3.0); - EXPECT_DOUBLE_EQ(p2.point.pose.orientation.z, 2.0); - EXPECT_DOUBLE_EQ(p2.point.pose.orientation.w, 1.0); - EXPECT_FLOAT_EQ(p2.point.longitudinal_velocity_mps, 2.1); - EXPECT_FLOAT_EQ(p2.point.lateral_velocity_mps, 4.3); - EXPECT_FLOAT_EQ(p2.point.heading_rate_rps, 6.5); - EXPECT_FALSE(p2.point.is_final); - EXPECT_EQ(p2.lane_ids.front(), 205); + const auto & p2 = path_points.back(); + EXPECT_DOUBLE_EQ(p2.point.pose.position.x, 0.0); + EXPECT_DOUBLE_EQ(p2.point.pose.position.y, 20.5); + EXPECT_DOUBLE_EQ(p2.point.pose.position.z, 90.11); + EXPECT_DOUBLE_EQ(p2.point.pose.orientation.x, 4.0); + EXPECT_DOUBLE_EQ(p2.point.pose.orientation.y, 3.0); + EXPECT_DOUBLE_EQ(p2.point.pose.orientation.z, 2.0); + EXPECT_DOUBLE_EQ(p2.point.pose.orientation.w, 1.0); + EXPECT_FLOAT_EQ(p2.point.longitudinal_velocity_mps, 2.1); + EXPECT_FLOAT_EQ(p2.point.lateral_velocity_mps, 4.3); + EXPECT_FLOAT_EQ(p2.point.heading_rate_rps, 6.5); + EXPECT_FALSE(p2.point.is_final); + EXPECT_EQ(p2.lane_ids.front(), 205); - EXPECT_DOUBLE_EQ(path.left_bound.front().x, 55.0); - EXPECT_DOUBLE_EQ(path.left_bound.front().y, 66.0); - EXPECT_DOUBLE_EQ(path.left_bound.front().z, 77.0); + EXPECT_DOUBLE_EQ(path.left_bound.front().x, 55.0); + EXPECT_DOUBLE_EQ(path.left_bound.front().y, 66.0); + EXPECT_DOUBLE_EQ(path.left_bound.front().z, 77.0); - EXPECT_DOUBLE_EQ(path.right_bound.front().x, 0.55); - EXPECT_DOUBLE_EQ(path.right_bound.front().y, 0.66); - EXPECT_DOUBLE_EQ(path.right_bound.front().z, 0.77); + EXPECT_DOUBLE_EQ(path.right_bound.front().x, 0.55); + EXPECT_DOUBLE_EQ(path.right_bound.front().y, 0.66); + EXPECT_DOUBLE_EQ(path.right_bound.front().z, 0.77); + } else { + FAIL() << "Yaml file might've corrupted."; + } } } // namespace autoware::test_utils diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 1526e061ca4d1..02e64e3ec84a0 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -279,9 +279,13 @@ void PlanningInterfaceTestManager::publishAbnormalRoute( void PlanningInterfaceTestManager::publishNominalPathWithLaneId( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, normal_path_with_lane_id_pub_, - autoware::test_utils::loadPathWithLaneIdInYaml(), 5); + try { + const auto path = autoware::test_utils::loadPathWithLaneIdInYaml(); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, normal_path_with_lane_id_pub_, path, 5); + } catch (const std::exception & e) { + std::cerr << e.what() << '\n'; + } } void PlanningInterfaceTestManager::publishAbNominalPathWithLaneId( @@ -294,11 +298,14 @@ void PlanningInterfaceTestManager::publishAbNominalPathWithLaneId( void PlanningInterfaceTestManager::publishNominalPath( rclcpp::Node::SharedPtr target_node, std::string topic_name) { - autoware::test_utils::publishToTargetNode( - test_node_, target_node, topic_name, normal_path_pub_, - autoware::motion_utils::convertToPath( - autoware::test_utils::loadPathWithLaneIdInYaml()), - 5); + try { + const auto path = autoware::test_utils::loadPathWithLaneIdInYaml(); + autoware::test_utils::publishToTargetNode( + test_node_, target_node, topic_name, normal_path_pub_, + autoware::motion_utils::convertToPath(path), 5); + } catch (const std::exception & e) { + std::cerr << e.what() << '\n'; + } } void PlanningInterfaceTestManager::publishAbnormalPath( diff --git a/planning/autoware_route_handler/test/test_route_handler.hpp b/planning/autoware_route_handler/test/test_route_handler.hpp index 1a9359dc8e17d..69d6a871959ca 100644 --- a/planning/autoware_route_handler/test/test_route_handler.hpp +++ b/planning/autoware_route_handler/test/test_route_handler.hpp @@ -45,7 +45,11 @@ class TestRouteHandler : public ::testing::Test TestRouteHandler() { set_route_handler("2km_test.osm"); - set_test_route(lane_change_right_test_route_filename); + try { + set_test_route(lane_change_right_test_route_filename); + } catch (const std::exception & e) { + std::cerr << e.what() << '\n'; + } } TestRouteHandler(const TestRouteHandler &) = delete; @@ -68,7 +72,14 @@ class TestRouteHandler : public ::testing::Test { const auto rh_test_route = get_absolute_path_to_route(autoware_route_handler_dir, route_filename); - route_handler_->setRoute(autoware::test_utils::parse(rh_test_route)); + if ( + const auto route_opt = + autoware::test_utils::parse>(rh_test_route)) { + route_handler_->setRoute(*route_opt); + } else { + throw std::runtime_error( + "Failed to parse YAML file: " + rh_test_route + ". The file might be corrupted."); + } } lanelet::ConstLanelets get_current_lanes() diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp index 0570349bc3df5..3becc2e4f4a69 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp @@ -126,7 +126,11 @@ class TestNormalLaneChange : public ::testing::Test auto route_handler_ptr = std::make_shared(map_bin_msg); const auto rh_test_route = get_absolute_path_to_route(autoware_route_handler_dir, lane_change_right_test_route_filename); - route_handler_ptr->setRoute(autoware::test_utils::parse(rh_test_route)); + if ( + const auto route_opt = + autoware::test_utils::parse>(rh_test_route)) { + route_handler_ptr->setRoute(*route_opt); + } return route_handler_ptr; } From 959e57be034e9045dda149ce2ebd5950fadfcd4a Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Tue, 3 Dec 2024 12:27:32 +0900 Subject: [PATCH 200/273] test(autoware_behavior_path_side_shift_module): add unit tests for util function (#9540) test(side_shift_module): add unit tests Signed-off-by: Kyoichi Sugahara --- .../CMakeLists.txt | 15 ++ .../src/scene.cpp | 1 + .../test/test_side_shift_utils.cpp | 142 ++++++++++++++++++ 3 files changed, 158 insertions(+) create mode 100644 planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_side_shift_utils.cpp diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CMakeLists.txt b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CMakeLists.txt index 520132dbd3363..334703e0edbb1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CMakeLists.txt +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CMakeLists.txt @@ -21,6 +21,21 @@ if(BUILD_TESTING) ) target_include_directories(test_${PROJECT_NAME} PRIVATE src) + + ament_add_ros_isolated_gtest(test_${PROJECT_NAME}_utils + test/test_side_shift_utils.cpp + ) + + target_include_directories(test_${PROJECT_NAME}_utils PRIVATE src) + + ament_target_dependencies(test_${PROJECT_NAME}_utils + tf2 + tf2_geometry_msgs + ) + + target_link_libraries(test_${PROJECT_NAME}_utils + ${PROJECT_NAME} + ) endif() ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index d855f1cdcde24..d640e5fc16771 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -341,6 +341,7 @@ BehaviorModuleOutput SideShiftModule::planWaitingApproval() return output; } +// can be moved to utils ShiftLine SideShiftModule::calcShiftLine() const { const auto & p = parameters_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_side_shift_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_side_shift_utils.cpp new file mode 100644 index 0000000000000..d6aa91d1f9095 --- /dev/null +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_side_shift_utils.cpp @@ -0,0 +1,142 @@ +// 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/behavior_path_side_shift_module/utils.hpp" + +#include + +#include +#include +#include + +namespace autoware::behavior_path_planner +{ + +class SideShiftUtilsTest : public ::testing::Test +{ +protected: + PathWithLaneId generateStraightPath(const double length, const double width) + { + PathWithLaneId path; + const double interval = 1.0; + const size_t point_num = static_cast(length / interval); + + for (size_t i = 0; i < point_num; ++i) { + PathPointWithLaneId p; + p.point.pose.position.x = i * interval; + p.point.pose.position.y = width; + p.point.pose.position.z = 0.0; + + tf2::Quaternion q; + q.setRPY(0, 0, 0); + p.point.pose.orientation.x = q.x(); + p.point.pose.orientation.y = q.y(); + p.point.pose.orientation.z = q.z(); + p.point.pose.orientation.w = q.w(); + + path.points.push_back(p); + } + return path; + } + + ShiftedPath generateShiftedPath(const double length, const std::vector & shifts) + { + ShiftedPath shifted_path; + shifted_path.path = generateStraightPath(length, 0.0); + shifted_path.shift_length = shifts; + return shifted_path; + } +}; + +TEST_F(SideShiftUtilsTest, SetOrientationStraightPath) +{ + // Generate straight path + auto path = generateStraightPath(10.0, 0.0); + + // Set orientation + setOrientation(&path); + + // Check orientation for each point + for (const auto & p : path.points) { + double yaw = tf2::getYaw(p.point.pose.orientation); + EXPECT_NEAR(yaw, 0.0, 1e-6); // Should be facing forward (0 rad) + } +} + +TEST_F(SideShiftUtilsTest, SetOrientationCurvedPath) +{ + PathWithLaneId path; + + // Create a 90-degree turn path + PathPointWithLaneId p1, p2, p3; + + p1.point.pose.position.x = 0.0; + p1.point.pose.position.y = 0.0; + p1.point.pose.position.z = 0.0; + + p2.point.pose.position.x = 1.0; + p2.point.pose.position.y = 0.0; + p2.point.pose.position.z = 0.0; + + p3.point.pose.position.x = 1.0; + p3.point.pose.position.y = 1.0; + p3.point.pose.position.z = 0.0; + + path.points = {p1, p2, p3}; + + setOrientation(&path); + + // First segment should face east (0 rad) + EXPECT_NEAR(tf2::getYaw(path.points[0].point.pose.orientation), 0.0, 1e-6); + + // Last segment should face north (π/2 rad) + EXPECT_NEAR(tf2::getYaw(path.points[2].point.pose.orientation), M_PI_2, 1e-6); +} + +TEST_F(SideShiftUtilsTest, GetClosestShiftLengthEmptyPath) +{ + ShiftedPath empty_path; + geometry_msgs::msg::Point ego_point; + ego_point.x = 0.0; + ego_point.y = 0.0; + + double shift = getClosestShiftLength(empty_path, ego_point); + EXPECT_DOUBLE_EQ(shift, 0.0); +} + +TEST_F(SideShiftUtilsTest, GetClosestShiftLengthStraightPath) +{ + // Generate path with constant shift + std::vector shifts(10, 2.0); // 10 points with 2.0m shift + auto shifted_path = generateShiftedPath(10.0, shifts); + + // Test points at different positions + geometry_msgs::msg::Point ego_point; + + // Point at start + ego_point.x = 0.0; + ego_point.y = 0.0; + EXPECT_DOUBLE_EQ(getClosestShiftLength(shifted_path, ego_point), 2.0); + + // Point in middle + ego_point.x = 5.0; + ego_point.y = 0.0; + EXPECT_DOUBLE_EQ(getClosestShiftLength(shifted_path, ego_point), 2.0); + + // Point at end + ego_point.x = 9.0; + ego_point.y = 0.0; + EXPECT_DOUBLE_EQ(getClosestShiftLength(shifted_path, ego_point), 2.0); +} + +} // namespace autoware::behavior_path_planner From 2a50825fafdf1c26d3cc52f7d79afb9a4db6f7f6 Mon Sep 17 00:00:00 2001 From: Mitsuhiro Sakamoto <50359861+mitukou1109@users.noreply.github.com> Date: Tue, 3 Dec 2024 14:57:37 +0900 Subject: [PATCH 201/273] test(lane_departure_checker): add tests for calcTrajectoryDeviation(), calcMaxSearchLengthForBoundaries() (#9029) * move calcTrajectoryDeviation() to separate files Signed-off-by: mitukou1109 * move calcMaxSearchLengthForBoundaries() to separate files Signed-off-by: mitukou1109 * add tests for calcTrajectoryDeviation() Signed-off-by: mitukou1109 * add tests for calcMaxSearchLengthForBoundaries() Signed-off-by: mitukou1109 --------- Signed-off-by: mitukou1109 Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> --- .../lane_departure_checker.hpp | 6 - .../autoware/lane_departure_checker/utils.hpp | 23 ++++ .../lane_departure_checker.cpp | 27 +---- .../src/lane_departure_checker_node/utils.cpp | 22 ++++ ..._calc_max_search_length_for_boundaries.cpp | 105 ++++++++++++++++++ .../test/test_calc_trajectory_deviation.cpp | 98 ++++++++++++++++ 6 files changed, 250 insertions(+), 31 deletions(-) create mode 100644 control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp create mode 100644 control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp index 6c83f8780c93c..da4784bb2458a 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp @@ -157,10 +157,6 @@ class LaneDepartureChecker Param param_; std::shared_ptr vehicle_info_ptr_; - static PoseDeviation calcTrajectoryDeviation( - const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, - const double dist_threshold, const double yaw_threshold); - static std::vector createVehiclePassingAreas( const std::vector & vehicle_footprints); @@ -168,8 +164,6 @@ class LaneDepartureChecker const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints) const; - double calcMaxSearchLengthForBoundaries(const Trajectory & trajectory) const; - static SegmentRtree extractUncrossableBoundaries( const lanelet::LaneletMap & lanelet_map, const geometry_msgs::msg::Point & ego_point, const double max_search_length, const std::vector & boundary_types_to_detect); diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/utils.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/utils.hpp index 45a651339cc12..944c57f66b8f1 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/utils.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/utils.hpp @@ -16,6 +16,7 @@ #define AUTOWARE__LANE_DEPARTURE_CHECKER__UTILS_HPP_ #include +#include #include #include @@ -28,6 +29,7 @@ namespace autoware::lane_departure_checker::utils { using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::PoseDeviation; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; using tier4_planning_msgs::msg::PathWithLaneId; @@ -73,6 +75,27 @@ std::vector createVehicleFootprints( std::vector createVehicleFootprints( const PathWithLaneId & path, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double footprint_extra_margin); + +/** + * @brief calculate the deviation of the given pose from the nearest pose on the trajectory + * @param trajectory target trajectory + * @param pose vehicle pose + * @param dist_threshold distance threshold used for searching for first nearest index to given pose + * @param yaw_threshold yaw threshold used for searching for first nearest index to given pose + * @return deviation of the given pose from the trajectory + */ +PoseDeviation calcTrajectoryDeviation( + const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, const double dist_threshold, + const double yaw_threshold); + +/** + * @brief calculate the maximum search length for boundaries considering the vehicle dimensions + * @param trajectory target trajectory + * @param vehicle_info vehicle information + * @return maximum search length for boundaries + */ +double calcMaxSearchLengthForBoundaries( + const Trajectory & trajectory, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info); } // namespace autoware::lane_departure_checker::utils #endif // AUTOWARE__LANE_DEPARTURE_CHECKER__UTILS_HPP_ diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index f823988c77e4d..a1ef24e32543f 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -16,7 +16,6 @@ #include "autoware/lane_departure_checker/utils.hpp" -#include #include #include #include @@ -29,7 +28,6 @@ #include #include -using autoware::motion_utils::calcArcLength; using autoware::universe_utils::LinearRing2d; using autoware::universe_utils::LineString2d; using autoware::universe_utils::MultiPoint2d; @@ -103,7 +101,7 @@ Output LaneDepartureChecker::update(const Input & input) autoware::universe_utils::StopWatch stop_watch; - output.trajectory_deviation = calcTrajectoryDeviation( + output.trajectory_deviation = utils::calcTrajectoryDeviation( *input.reference_trajectory, input.current_odom->pose.pose, param_.ego_nearest_dist_threshold, param_.ego_nearest_yaw_threshold); output.processing_time_map["calcTrajectoryDeviation"] = stop_watch.toc(true); @@ -148,7 +146,7 @@ Output LaneDepartureChecker::update(const Input & input) output.processing_time_map["isOutOfLane"] = stop_watch.toc(true); const double max_search_length_for_boundaries = - calcMaxSearchLengthForBoundaries(*input.predicted_trajectory); + utils::calcMaxSearchLengthForBoundaries(*input.predicted_trajectory, *vehicle_info_ptr_); const auto uncrossable_boundaries = extractUncrossableBoundaries( *input.lanelet_map, input.predicted_trajectory->points.front().pose.position, max_search_length_for_boundaries, input.boundary_types_to_detect); @@ -169,15 +167,6 @@ bool LaneDepartureChecker::checkPathWillLeaveLane( return willLeaveLane(candidate_lanelets, vehicle_footprints); } -PoseDeviation LaneDepartureChecker::calcTrajectoryDeviation( - const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, const double dist_threshold, - const double yaw_threshold) -{ - const auto nearest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( - trajectory.points, pose, dist_threshold, yaw_threshold); - return autoware::universe_utils::calcPoseDeviation(trajectory.points.at(nearest_idx).pose, pose); -} - std::vector LaneDepartureChecker::createVehiclePassingAreas( const std::vector & vehicle_footprints) { @@ -388,18 +377,6 @@ bool LaneDepartureChecker::isOutOfLane( return false; } -double LaneDepartureChecker::calcMaxSearchLengthForBoundaries(const Trajectory & trajectory) const -{ - const double max_ego_lon_length = std::max( - std::abs(vehicle_info_ptr_->max_longitudinal_offset_m), - std::abs(vehicle_info_ptr_->min_longitudinal_offset_m)); - const double max_ego_lat_length = std::max( - std::abs(vehicle_info_ptr_->max_lateral_offset_m), - std::abs(vehicle_info_ptr_->min_lateral_offset_m)); - const double max_ego_search_length = std::hypot(max_ego_lon_length, max_ego_lat_length); - return calcArcLength(trajectory.points) + max_ego_search_length; -} - SegmentRtree LaneDepartureChecker::extractUncrossableBoundaries( const lanelet::LaneletMap & lanelet_map, const geometry_msgs::msg::Point & ego_point, const double max_search_length, const std::vector & boundary_types_to_detect) diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp index 324936c633158..19ea23ccd19da 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp @@ -14,6 +14,7 @@ #include "autoware/lane_departure_checker/utils.hpp" +#include #include #include @@ -161,4 +162,25 @@ std::vector createVehicleFootprints( return vehicle_footprints; } + +PoseDeviation calcTrajectoryDeviation( + const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, const double dist_threshold, + const double yaw_threshold) +{ + const auto nearest_idx = autoware::motion_utils::findFirstNearestIndexWithSoftConstraints( + trajectory.points, pose, dist_threshold, yaw_threshold); + return autoware::universe_utils::calcPoseDeviation(trajectory.points.at(nearest_idx).pose, pose); +} + +double calcMaxSearchLengthForBoundaries( + const Trajectory & trajectory, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info) +{ + const double max_ego_lon_length = std::max( + std::abs(vehicle_info.max_longitudinal_offset_m), + std::abs(vehicle_info.min_longitudinal_offset_m)); + const double max_ego_lat_length = std::max( + std::abs(vehicle_info.max_lateral_offset_m), std::abs(vehicle_info.min_lateral_offset_m)); + const double max_ego_search_length = std::hypot(max_ego_lon_length, max_ego_lat_length); + return autoware::motion_utils::calcArcLength(trajectory.points) + max_ego_search_length; +} } // namespace autoware::lane_departure_checker::utils diff --git a/control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp b/control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp new file mode 100644 index 0000000000000..1632f41f35153 --- /dev/null +++ b/control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp @@ -0,0 +1,105 @@ +// 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/lane_departure_checker/utils.hpp" + +#include + +#include + +using autoware_planning_msgs::msg::Trajectory; +using autoware_planning_msgs::msg::TrajectoryPoint; + +namespace +{ +Trajectory create_trajectory(const std::vector & points) +{ + Trajectory trajectory; + for (const auto & point : points) { + TrajectoryPoint p; + p.pose.position.x = point.x(); + p.pose.position.y = point.y(); + trajectory.points.push_back(p); + } + return trajectory; +} + +// reference: +// https://github.com/autowarefoundation/sample_vehicle_launch/blob/main/sample_vehicle_description/config/vehicle_info.param.yaml +constexpr double wheel_radius_m = 0.383; +constexpr double wheel_width_m = 0.235; +constexpr double wheel_base_m = 2.79; +constexpr double wheel_tread_m = 1.64; +constexpr double front_overhang_m = 1.0; +constexpr double rear_overhang_m = 1.1; +constexpr double left_overhang_m = 0.128; +constexpr double right_overhang_m = 0.128; +constexpr double vehicle_height_m = 2.5; +constexpr double max_steer_angle_rad = 0.70; +} // namespace + +struct CalcMaxSearchLengthForBoundariesParam +{ + std::string description; + std::vector trajectory_points; + double expected_max_search_length; +}; + +std::ostream & operator<<(std::ostream & os, const CalcMaxSearchLengthForBoundariesParam & p) +{ + return os << p.description; +} + +class CalcMaxSearchLengthForBoundariesTest +: public ::testing::TestWithParam +{ +protected: + void SetUp() override + { + vehicle_info = autoware::vehicle_info_utils::createVehicleInfo( + wheel_radius_m, wheel_width_m, wheel_base_m, wheel_tread_m, front_overhang_m, rear_overhang_m, + left_overhang_m, right_overhang_m, vehicle_height_m, max_steer_angle_rad); + } + + autoware::vehicle_info_utils::VehicleInfo vehicle_info; +}; + +TEST_P(CalcMaxSearchLengthForBoundariesTest, test_calc_max_search_length_for_boundaries) +{ + const auto p = GetParam(); + const auto trajectory = create_trajectory(p.trajectory_points); + + const auto max_search_length = + autoware::lane_departure_checker::utils::calcMaxSearchLengthForBoundaries( + trajectory, vehicle_info); + + EXPECT_DOUBLE_EQ(max_search_length, p.expected_max_search_length); +} + +INSTANTIATE_TEST_SUITE_P( + LaneDepartureCheckerTest, CalcMaxSearchLengthForBoundariesTest, + ::testing::Values( + CalcMaxSearchLengthForBoundariesParam{ + "EmptyTrajectory", + {}, + std::hypot(front_overhang_m + wheel_base_m, wheel_tread_m / 2.0 + left_overhang_m)}, + CalcMaxSearchLengthForBoundariesParam{ + "SinglePointTrajectory", + {{0.0, 0.0}}, + std::hypot(front_overhang_m + wheel_base_m, wheel_tread_m / 2.0 + left_overhang_m)}, + CalcMaxSearchLengthForBoundariesParam{ + "MultiPointTrajectory", + {{0.0, 0.0}, {1.0, 0.0}}, + 1.0 + std::hypot(front_overhang_m + wheel_base_m, wheel_tread_m / 2.0 + left_overhang_m)}), + ::testing::PrintToStringParamName()); diff --git a/control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp b/control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp new file mode 100644 index 0000000000000..a0f141e9639a9 --- /dev/null +++ b/control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp @@ -0,0 +1,98 @@ +// 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/lane_departure_checker/utils.hpp" + +#include + +#include + +using autoware::universe_utils::PoseDeviation; +using autoware_planning_msgs::msg::Trajectory; +using autoware_planning_msgs::msg::TrajectoryPoint; + +namespace +{ +Trajectory create_trajectory(const std::vector & points) +{ + Trajectory trajectory; + for (const auto & point : points) { + TrajectoryPoint p; + p.pose.position.x = point.x(); + p.pose.position.y = point.y(); + trajectory.points.push_back(p); + } + return trajectory; +} + +geometry_msgs::msg::Pose create_pose(const Eigen::Vector3d & x_y_yaw) +{ + geometry_msgs::msg::Pose pose; + pose.position.x = x_y_yaw[0]; + pose.position.y = x_y_yaw[1]; + pose.orientation.z = std::sin(x_y_yaw[2] / 2); + pose.orientation.w = std::cos(x_y_yaw[2] / 2); + return pose; +} + +constexpr double ego_nearest_dist_threshold = 3.0; +constexpr double ego_nearest_yaw_threshold = 1.046; +} // namespace + +struct CalcTrajectoryDeviationTestParam +{ + std::string description; + std::vector trajectory_points; + Eigen::Vector3d x_y_yaw; + bool exception_expected; + PoseDeviation expected_deviation; +}; + +std::ostream & operator<<(std::ostream & os, const CalcTrajectoryDeviationTestParam & p) +{ + return os << p.description; +} + +class CalcTrajectoryDeviationTest +: public ::testing::TestWithParam +{ +}; + +TEST_P(CalcTrajectoryDeviationTest, test_calc_trajectory_deviation) +{ + const auto p = GetParam(); + const auto trajectory = create_trajectory(p.trajectory_points); + const auto pose = create_pose(p.x_y_yaw); + if (p.exception_expected) { + EXPECT_ANY_THROW({ + autoware::lane_departure_checker::utils::calcTrajectoryDeviation( + trajectory, pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); + }); + } else { + const auto deviation = autoware::lane_departure_checker::utils::calcTrajectoryDeviation( + trajectory, pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); + + EXPECT_DOUBLE_EQ(deviation.lateral, p.expected_deviation.lateral); + EXPECT_DOUBLE_EQ(deviation.longitudinal, p.expected_deviation.longitudinal); + EXPECT_DOUBLE_EQ(deviation.yaw, p.expected_deviation.yaw); + } +} + +INSTANTIATE_TEST_SUITE_P( + LaneDepartureCheckerTest, CalcTrajectoryDeviationTest, + ::testing::Values( + CalcTrajectoryDeviationTestParam{"EmptyTrajectory", {}, {}, true, {}}, + CalcTrajectoryDeviationTestParam{ + "SinglePointTrajectory", {{0.0, 0.0}}, {0.0, 0.0, 0.0}, false, {0.0, 0.0, 0.0}}), + ::testing::PrintToStringParamName()); From dc759363c427f5be243a8bc9eb70ed51ebe9bfd2 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 3 Dec 2024 06:02:48 +0000 Subject: [PATCH 202/273] chore: update CODEOWNERS (#9541) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 6ac99a0243921..b2d0098cfecec 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -174,7 +174,7 @@ planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/** planning/behavior_path_planner/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_planner/autoware_behavior_path_start_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp -planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp +planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp yukinari.hisaki.2@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yuki.takagi@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yukinari.hisaki.2@tier4.jp From de11b6e7b5b00d08cf3d82ca4ff1df9cb141b3ec Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Tue, 3 Dec 2024 15:49:12 +0900 Subject: [PATCH 203/273] ci(clang-tidy): enable clang-tidy checks in perception (#9537) Signed-off-by: veqcc --- .clang-tidy-ignore | 1 - 1 file changed, 1 deletion(-) diff --git a/.clang-tidy-ignore b/.clang-tidy-ignore index a7110b007db10..f10528128dce6 100644 --- a/.clang-tidy-ignore +++ b/.clang-tidy-ignore @@ -1,2 +1 @@ */examples/* -perception/* From c332e7e45d4bc1daa23b59cbcdb642139f44f71c Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Tue, 3 Dec 2024 09:00:34 +0100 Subject: [PATCH 204/273] fix(scenario_simulator_v2_adapter): remove invalid CHANGELOG.rst file (#9501) Signed-off-by: Esteve Fernandez --- .../CHANGELOG.rst | 80 ------------------- 1 file changed, 80 deletions(-) delete mode 100644 evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst diff --git a/evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst b/evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst deleted file mode 100644 index 0c41ad6263d8b..0000000000000 --- a/evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst +++ /dev/null @@ -1,80 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package diagnostic_converter -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* Contributors: Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- -* fix(diagnostic_converter): move headers to a separate directory (`#5943 `_) - * fix(diagnostic_converter): move headers to a separate directory - * style(pre-commit): autofix - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> -* build: mark autoware_cmake as (`#3616 `_) - * build: mark autoware_cmake as - with , autoware_cmake is automatically exported with ament_target_dependencies() (unecessary) - * style(pre-commit): autofix - * chore: fix pre-commit errors - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> - Co-authored-by: Kenji Miyake -* feat(diagnostic_converter): remove unit and blank in the value (`#3151 `_) - * feat(diagnostic_converter): remove unit and blank in the value - * fix - --------- -* feat(diagnostic_converter): apply regex for topic name (`#3149 `_) -* feat(diagnostic_converter): add converter to use planning_evaluator's output for scenario's condition (`#2514 `_) - * add original diagnostic_convertor - * add test - * fix typo - * delete file - * change include - * temp - * delete comments - * made launch for converter - * ci(pre-commit): autofix - * ci(pre-commit): autofix - * add diagnostic convertor in launch - * ci(pre-commit): autofix - * change debug from info - * change arg name to launch diagnostic convertor - * add planning_evaluator launcher in simulator.launch.xml - * fix arg wrong setting - * style(pre-commit): autofix - * use simulation msg in tier4_autoware_msgs - * style(pre-commit): autofix - * fix README - * style(pre-commit): autofix - * refactoring - * style(pre-commit): autofix - * remove unnecessary dependency - * remove unnecessary dependency - * move folder - * reformat - * style(pre-commit): autofix - * Update evaluator/diagnostic_converter/include/converter_node.hpp - Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> - * Update evaluator/diagnostic_converter/README.md - Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> - * Update evaluator/diagnostic_converter/src/converter_node.cpp - Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> - * Update evaluator/diagnostic_converter/test/test_converter_node.cpp - Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> - * define diagnostic_topics as parameter - * fix include way - * fix include way - * delete ament_cmake_clang_format from package.xml - * fix test_depend - * Update evaluator/diagnostic_converter/test/test_converter_node.cpp - Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> - * style(pre-commit): autofix - * Update launch/tier4_simulator_launch/launch/simulator.launch.xml - Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> - --------- - Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> - Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> -* Contributors: Esteve Fernandez, Kyoichi Sugahara, Takayuki Murooka, Vincent Richard From e5116056ce0761fe1ff432e0a0c35f5ce53467b3 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Tue, 3 Dec 2024 18:04:20 +0900 Subject: [PATCH 205/273] chore(image_projection_based_fusion): add debug for roi_pointcloud fusion (#9481) Signed-off-by: badai-nguyen --- .../src/roi_pointcloud_fusion/node.cpp | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index 039e4f7591bbc..1f362da89f7a8 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -85,6 +85,8 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( if (!checkCameraInfo(camera_info)) return; std::vector output_objs; + std::vector debug_image_rois; + std::vector debug_image_points; // select ROIs for fusion for (const auto & feature_obj : input_roi_msg.feature_objects) { if (fuse_unknown_only_) { @@ -92,10 +94,12 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( autoware_perception_msgs::msg::ObjectClassification::UNKNOWN; if (is_roi_label_unknown) { output_objs.push_back(feature_obj); + debug_image_rois.push_back(feature_obj.feature.roi); } } else { // TODO(badai-nguyen): selected class from a list output_objs.push_back(feature_obj); + debug_image_rois.push_back(feature_obj.feature.roi); } } if (output_objs.empty()) { @@ -166,12 +170,25 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( clusters_data_size.at(i) += point_step; } } + if (debugger_) { + // add all points inside image to debug + if ( + projected_point.x() > 0 && projected_point.x() < camera_info.width && + projected_point.y() > 0 && projected_point.y() < camera_info.height) { + debug_image_points.push_back(projected_point); + } + } } // refine and update output_fused_objects_ updateOutputFusedObjects( output_objs, clusters, clusters_data_size, input_pointcloud_msg, input_roi_msg.header, tf_buffer_, min_cluster_size_, max_cluster_size_, cluster_2d_tolerance_, output_fused_objects_); + if (debugger_) { + debugger_->image_rois_ = debug_image_rois; + debugger_->obstacle_points_ = debug_image_points; + debugger_->publishImage(image_id, input_roi_msg.header.stamp); + } } bool RoiPointCloudFusionNode::out_of_scope(__attribute__((unused)) From 282a01d3f6400b4e491da862ad9f6793ab802c75 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Tue, 3 Dec 2024 21:02:25 +0900 Subject: [PATCH 206/273] feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (#9392) Signed-off-by: Ryohsuke Mitsudome --- build_depends.repos | 2 +- .../component_interface_specs/map.hpp | 4 +-- .../package.xml | 2 +- .../geography_utils/lanelet2_projector.hpp | 4 +-- .../autoware/geography_utils/projection.hpp | 4 +-- common/autoware_geography_utils/package.xml | 2 +- .../test/test_projection.cpp | 30 +++++++++--------- .../autoware_geo_pose_projector/README.md | 2 +- .../package.xml | 1 - map/autoware_map_loader/README.md | 4 +-- .../map_loader/lanelet2_map_loader_node.hpp | 4 +-- map/autoware_map_loader/package.xml | 1 - .../lanelet2_map_loader_node.cpp | 6 ++-- map/autoware_map_projection_loader/README.md | 4 +-- .../load_info_from_lanelet2_map.hpp | 4 +-- .../map_projection_loader.hpp | 4 +-- .../package.xml | 2 +- .../src/load_info_from_lanelet2_map.cpp | 12 +++---- .../src/map_projection_loader.cpp | 31 ++++++++++++------- .../test/data/map_projector_info_local.yaml | 2 +- .../test/test_load_info_from_lanelet2_map.cpp | 2 +- ...load_local_cartesian_utm_from_yaml.test.py | 2 +- .../test_node_load_local_from_yaml.test.py | 2 +- .../test_node_load_mgrs_from_yaml.test.py | 2 +- ...load_transverse_mercator_from_yaml.test.py | 2 +- .../package.xml | 1 - .../src/static_centerline_generator_node.hpp | 4 +-- sensing/autoware_gnss_poser/README.md | 2 +- simulator/autoware_carla_interface/README.md | 2 +- 29 files changed, 75 insertions(+), 69 deletions(-) diff --git a/build_depends.repos b/build_depends.repos index 61a56463e2e41..4db947b7c26a8 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -24,7 +24,7 @@ repositories: core/autoware_msgs: type: git url: https://github.com/autowarefoundation/autoware_msgs.git - version: 1.1.0 + version: 1.3.0 core/autoware_adapi_msgs: type: git url: https://github.com/autowarefoundation/autoware_adapi_msgs.git diff --git a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp index dd1c300a7a2ca..aeb09e44c665f 100644 --- a/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp +++ b/common/autoware_component_interface_specs/include/autoware/component_interface_specs/map.hpp @@ -17,14 +17,14 @@ #include -#include +#include namespace autoware::component_interface_specs::map { struct MapProjectorInfo { - using Message = tier4_map_msgs::msg::MapProjectorInfo; + using Message = autoware_map_msgs::msg::MapProjectorInfo; static constexpr char name[] = "/map/map_projector_info"; static constexpr size_t depth = 1; static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; diff --git a/common/autoware_component_interface_specs/package.xml b/common/autoware_component_interface_specs/package.xml index b50cd80074d1f..0fbd632d52af3 100644 --- a/common/autoware_component_interface_specs/package.xml +++ b/common/autoware_component_interface_specs/package.xml @@ -12,6 +12,7 @@ autoware_cmake autoware_adapi_v1_msgs + autoware_map_msgs autoware_perception_msgs autoware_planning_msgs autoware_vehicle_msgs @@ -21,7 +22,6 @@ rosidl_runtime_cpp tier4_control_msgs tier4_localization_msgs - tier4_map_msgs tier4_planning_msgs tier4_system_msgs tier4_vehicle_msgs diff --git a/common/autoware_geography_utils/include/autoware/geography_utils/lanelet2_projector.hpp b/common/autoware_geography_utils/include/autoware/geography_utils/lanelet2_projector.hpp index 7f6b2d78701d2..0eea2a9ff7fbb 100644 --- a/common/autoware_geography_utils/include/autoware/geography_utils/lanelet2_projector.hpp +++ b/common/autoware_geography_utils/include/autoware/geography_utils/lanelet2_projector.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__GEOGRAPHY_UTILS__LANELET2_PROJECTOR_HPP_ #define AUTOWARE__GEOGRAPHY_UTILS__LANELET2_PROJECTOR_HPP_ -#include +#include #include @@ -23,7 +23,7 @@ namespace autoware::geography_utils { -using MapProjectorInfo = tier4_map_msgs::msg::MapProjectorInfo; +using MapProjectorInfo = autoware_map_msgs::msg::MapProjectorInfo; std::unique_ptr get_lanelet2_projector(const MapProjectorInfo & projector_info); diff --git a/common/autoware_geography_utils/include/autoware/geography_utils/projection.hpp b/common/autoware_geography_utils/include/autoware/geography_utils/projection.hpp index 5ad605f95f65b..5c4a69b15e192 100644 --- a/common/autoware_geography_utils/include/autoware/geography_utils/projection.hpp +++ b/common/autoware_geography_utils/include/autoware/geography_utils/projection.hpp @@ -15,13 +15,13 @@ #ifndef AUTOWARE__GEOGRAPHY_UTILS__PROJECTION_HPP_ #define AUTOWARE__GEOGRAPHY_UTILS__PROJECTION_HPP_ +#include #include #include -#include namespace autoware::geography_utils { -using MapProjectorInfo = tier4_map_msgs::msg::MapProjectorInfo; +using MapProjectorInfo = autoware_map_msgs::msg::MapProjectorInfo; using GeoPoint = geographic_msgs::msg::GeoPoint; using LocalPoint = geometry_msgs::msg::Point; diff --git a/common/autoware_geography_utils/package.xml b/common/autoware_geography_utils/package.xml index d8ea7524eaebc..8777bf4c13d45 100644 --- a/common/autoware_geography_utils/package.xml +++ b/common/autoware_geography_utils/package.xml @@ -17,11 +17,11 @@ autoware_cmake autoware_lanelet2_extension + autoware_map_msgs geographic_msgs geographiclib geometry_msgs lanelet2_io - tier4_map_msgs ament_cmake_ros ament_lint_auto diff --git a/common/autoware_geography_utils/test/test_projection.cpp b/common/autoware_geography_utils/test/test_projection.cpp index 3355dbf8a50ea..b8d036c136eeb 100644 --- a/common/autoware_geography_utils/test/test_projection.cpp +++ b/common/autoware_geography_utils/test/test_projection.cpp @@ -34,10 +34,10 @@ TEST(GeographyUtilsProjection, ProjectForwardToMGRS) local_point.z = 10.0; // projector info - tier4_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS; + autoware_map_msgs::msg::MapProjectorInfo projector_info; + projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::MGRS; projector_info.mgrs_grid = "54SUE"; - projector_info.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84; + projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; // conversion const geometry_msgs::msg::Point converted_point = @@ -63,10 +63,10 @@ TEST(GeographyUtilsProjection, ProjectReverseFromMGRS) geo_point.altitude = 10.0; // projector info - tier4_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS; + autoware_map_msgs::msg::MapProjectorInfo projector_info; + projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::MGRS; projector_info.mgrs_grid = "54SUE"; - projector_info.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84; + projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; // conversion const geographic_msgs::msg::GeoPoint converted_point = @@ -86,10 +86,10 @@ TEST(GeographyUtilsProjection, ProjectForwardAndReverseMGRS) geo_point.altitude = 10.0; // projector info - tier4_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS; + autoware_map_msgs::msg::MapProjectorInfo projector_info; + projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::MGRS; projector_info.mgrs_grid = "54SUE"; - projector_info.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84; + projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; // conversion const geometry_msgs::msg::Point converted_local_point = @@ -117,9 +117,9 @@ TEST(GeographyUtilsProjection, ProjectForwardToLocalCartesianUTMOrigin) local_point.z = 20.0; // projector info - tier4_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM; - projector_info.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84; + autoware_map_msgs::msg::MapProjectorInfo projector_info; + projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM; + projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; projector_info.map_origin.latitude = 35.62426; projector_info.map_origin.longitude = 139.74252; projector_info.map_origin.altitude = -10.0; @@ -142,9 +142,9 @@ TEST(GeographyUtilsProjection, ProjectForwardAndReverseLocalCartesianUTMOrigin) geo_point.altitude = 10.0; // projector info - tier4_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM; - projector_info.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84; + autoware_map_msgs::msg::MapProjectorInfo projector_info; + projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM; + projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; projector_info.map_origin.latitude = 35.0; projector_info.map_origin.longitude = 139.0; projector_info.map_origin.altitude = 0.0; diff --git a/localization/autoware_geo_pose_projector/README.md b/localization/autoware_geo_pose_projector/README.md index 2dd83a2077aab..a3cc5d3b308e3 100644 --- a/localization/autoware_geo_pose_projector/README.md +++ b/localization/autoware_geo_pose_projector/README.md @@ -9,7 +9,7 @@ This node is a simple node that subscribes to the geo-referenced pose topic and | Name | Type | Description | | ------------------------- | ---------------------------------------------------- | ------------------- | | `input_geo_pose` | `geographic_msgs::msg::GeoPoseWithCovarianceStamped` | geo-referenced pose | -| `/map/map_projector_info` | `tier4_map_msgs::msg::MapProjectedObjectInfo` | map projector info | +| `/map/map_projector_info` | `autoware_map_msgs::msg::MapProjectedObjectInfo` | map projector info | ## Published Topics diff --git a/map/autoware_lanelet2_map_visualizer/package.xml b/map/autoware_lanelet2_map_visualizer/package.xml index 0244a5f010aa4..3c3bb24c18399 100644 --- a/map/autoware_lanelet2_map_visualizer/package.xml +++ b/map/autoware_lanelet2_map_visualizer/package.xml @@ -24,7 +24,6 @@ autoware_map_msgs rclcpp rclcpp_components - tier4_map_msgs visualization_msgs ament_lint_auto diff --git a/map/autoware_map_loader/README.md b/map/autoware_map_loader/README.md index 046c9062081ca..ec06ee4d824c7 100644 --- a/map/autoware_map_loader/README.md +++ b/map/autoware_map_loader/README.md @@ -132,7 +132,7 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co lanelet2_map_loader loads Lanelet2 file and publishes the map data as autoware_map_msgs/LaneletMapBin message. The node projects lan/lon coordinates into arbitrary coordinates defined in `/map/map_projector_info` from `map_projection_loader`. -Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tier4/tier4_autoware_msgs/blob/tier4/universe/tier4_map_msgs/msg/MapProjectorInfo.msg) for supported projector types. +Please see [autoware_map_msgs/msg/MapProjectorInfo.msg](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_map_msgs/msg/MapProjectorInfo.msg) for supported projector types. ### How to run @@ -140,7 +140,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie ### Subscribed Topics -- ~input/map_projector_info (tier4_map_msgs/MapProjectorInfo) : Projection type for Autoware +- ~input/map_projector_info (autoware_map_msgs/MapProjectorInfo) : Projection type for Autoware ### Published Topics diff --git a/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp b/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp index 54d8244ff76e0..0922b1cb2bdd6 100644 --- a/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp +++ b/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp @@ -21,7 +21,7 @@ #include #include -#include +#include #include @@ -40,7 +40,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node static lanelet::LaneletMapPtr load_map( const std::string & lanelet2_filename, - const tier4_map_msgs::msg::MapProjectorInfo & projector_info); + const autoware_map_msgs::msg::MapProjectorInfo & projector_info); static autoware_map_msgs::msg::LaneletMapBin create_map_bin_msg( const lanelet::LaneletMapPtr map, const std::string & lanelet2_filename, const rclcpp::Time & now); diff --git a/map/autoware_map_loader/package.xml b/map/autoware_map_loader/package.xml index 15fc9fd13df64..7b793359d725b 100644 --- a/map/autoware_map_loader/package.xml +++ b/map/autoware_map_loader/package.xml @@ -30,7 +30,6 @@ pcl_conversions rclcpp rclcpp_components - tier4_map_msgs visualization_msgs yaml-cpp diff --git a/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index ee1cc4a58a1be..0d431e65de3dc 100644 --- a/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -55,7 +55,7 @@ namespace autoware::map_loader { using autoware_map_msgs::msg::LaneletMapBin; -using tier4_map_msgs::msg::MapProjectorInfo; +using autoware_map_msgs::msg::MapProjectorInfo; Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options) : Node("lanelet2_map_loader", options) @@ -136,10 +136,10 @@ void Lanelet2MapLoaderNode::on_map_projector_info( lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( const std::string & lanelet2_filename, - const tier4_map_msgs::msg::MapProjectorInfo & projector_info) + const autoware_map_msgs::msg::MapProjectorInfo & projector_info) { lanelet::ErrorMessages errors{}; - if (projector_info.projector_type != tier4_map_msgs::msg::MapProjectorInfo::LOCAL) { + if (projector_info.projector_type != autoware_map_msgs::msg::MapProjectorInfo::LOCAL) { std::unique_ptr projector = autoware::geography_utils::get_lanelet2_projector(projector_info); lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, *projector, &errors); diff --git a/map/autoware_map_projection_loader/README.md b/map/autoware_map_projection_loader/README.md index 2568bb2c17df7..ad35a666eb0b8 100644 --- a/map/autoware_map_projection_loader/README.md +++ b/map/autoware_map_projection_loader/README.md @@ -29,7 +29,7 @@ There are three types of transformations from latitude and longitude to XYZ coor ```yaml # map_projector_info.yaml -projector_type: local +projector_type: Local ``` #### Limitation @@ -86,7 +86,7 @@ map_origin: ## Published Topics -- `~/map_projector_info` (tier4_map_msgs/MapProjectorInfo) : This topic shows the definition of map projector information +- `~/map_projector_info` (autoware_map_msgs/MapProjectorInfo) : This topic shows the definition of map projector information ## Parameters diff --git a/map/autoware_map_projection_loader/include/autoware/map_projection_loader/load_info_from_lanelet2_map.hpp b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/load_info_from_lanelet2_map.hpp index 2f1db14529ad0..da0ebb83748ab 100644 --- a/map/autoware_map_projection_loader/include/autoware/map_projection_loader/load_info_from_lanelet2_map.hpp +++ b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/load_info_from_lanelet2_map.hpp @@ -20,13 +20,13 @@ #include #include -#include "tier4_map_msgs/msg/map_projector_info.hpp" +#include "autoware_map_msgs/msg/map_projector_info.hpp" #include namespace autoware::map_projection_loader { -tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename); +autoware_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename); } // namespace autoware::map_projection_loader #endif // AUTOWARE__MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_ diff --git a/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp index 6ef9213cf33f8..1ca876dc035b2 100644 --- a/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp +++ b/map/autoware_map_projection_loader/include/autoware/map_projection_loader/map_projection_loader.hpp @@ -24,8 +24,8 @@ namespace autoware::map_projection_loader { -tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename); -tier4_map_msgs::msg::MapProjectorInfo load_map_projector_info( +autoware_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename); +autoware_map_msgs::msg::MapProjectorInfo load_map_projector_info( const std::string & yaml_filename, const std::string & lanelet2_map_filename); class MapProjectionLoader : public rclcpp::Node diff --git a/map/autoware_map_projection_loader/package.xml b/map/autoware_map_projection_loader/package.xml index 55785a81ea1a2..ddf95efc7414c 100644 --- a/map/autoware_map_projection_loader/package.xml +++ b/map/autoware_map_projection_loader/package.xml @@ -19,9 +19,9 @@ autoware_component_interface_specs autoware_component_interface_utils autoware_lanelet2_extension + autoware_map_msgs rclcpp rclcpp_components - tier4_map_msgs yaml-cpp ament_cmake_gmock diff --git a/map/autoware_map_projection_loader/src/load_info_from_lanelet2_map.cpp b/map/autoware_map_projection_loader/src/load_info_from_lanelet2_map.cpp index ce4cda5c2c677..750a73c8a8ec6 100644 --- a/map/autoware_map_projection_loader/src/load_info_from_lanelet2_map.cpp +++ b/map/autoware_map_projection_loader/src/load_info_from_lanelet2_map.cpp @@ -14,7 +14,7 @@ #include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp" -#include "tier4_map_msgs/msg/map_projector_info.hpp" +#include "autoware_map_msgs/msg/map_projector_info.hpp" #include #include @@ -25,7 +25,7 @@ namespace autoware::map_projection_loader { -tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename) +autoware_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename) { lanelet::ErrorMessages errors{}; lanelet::projection::MGRSProjector projector{}; @@ -46,18 +46,18 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::str } } - tier4_map_msgs::msg::MapProjectorInfo msg; + autoware_map_msgs::msg::MapProjectorInfo msg; if (is_local) { - msg.projector_type = tier4_map_msgs::msg::MapProjectorInfo::LOCAL; + msg.projector_type = autoware_map_msgs::msg::MapProjectorInfo::LOCAL; } else { - msg.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS; + msg.projector_type = autoware_map_msgs::msg::MapProjectorInfo::MGRS; msg.mgrs_grid = projector.getProjectedMGRSGrid(); } // We assume that the vertical datum of the map is WGS84 when using lanelet2 map. // However, do note that this is not always true, and may cause problems in the future. // Thus, please consider using the map_projector_info.yaml instead of this deprecated function. - msg.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84; + msg.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; return msg; } } // namespace autoware::map_projection_loader diff --git a/map/autoware_map_projection_loader/src/map_projection_loader.cpp b/map/autoware_map_projection_loader/src/map_projection_loader.cpp index 588ede616a814..a59714e627e83 100644 --- a/map/autoware_map_projection_loader/src/map_projection_loader.cpp +++ b/map/autoware_map_projection_loader/src/map_projection_loader.cpp @@ -16,7 +16,7 @@ #include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp" -#include +#include #include @@ -25,39 +25,48 @@ namespace autoware::map_projection_loader { -tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename) +autoware_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename) { YAML::Node data = YAML::LoadFile(filename); - tier4_map_msgs::msg::MapProjectorInfo msg; + autoware_map_msgs::msg::MapProjectorInfo msg; msg.projector_type = data["projector_type"].as(); - if (msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::MGRS) { + if (msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::MGRS) { msg.vertical_datum = data["vertical_datum"].as(); msg.mgrs_grid = data["mgrs_grid"].as(); } else if ( - msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM || - msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::TRANSVERSE_MERCATOR) { + msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM || + msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::TRANSVERSE_MERCATOR) { msg.vertical_datum = data["vertical_datum"].as(); msg.map_origin.latitude = data["map_origin"]["latitude"].as(); msg.map_origin.longitude = data["map_origin"]["longitude"].as(); msg.map_origin.altitude = data["map_origin"]["altitude"].as(); - } else if (msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL) { + } else if (msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL) { ; // do nothing + } else if (msg.projector_type == "local") { + RCLCPP_WARN_STREAM( + rclcpp::get_logger("MapProjectionLoader"), + "Load " << filename << "\n" + << "DEPRECATED WARNING: projector type \"local\" is deprecated." + "Please use \"Local\" instead. For more info, visit " + "https://github.com/autowarefoundation/autoware.universe/blob/main/map/" + "map_projection_loader README.md"); + msg.projector_type = autoware_map_msgs::msg::MapProjectorInfo::LOCAL; } else { throw std::runtime_error( "Invalid map projector type. Currently supported types: MGRS, LocalCartesianUTM, " - "TransverseMercator, and local"); + "TransverseMercator, and Local"); } return msg; } -tier4_map_msgs::msg::MapProjectorInfo load_map_projector_info( +autoware_map_msgs::msg::MapProjectorInfo load_map_projector_info( const std::string & yaml_filename, const std::string & lanelet2_map_filename) { - tier4_map_msgs::msg::MapProjectorInfo msg; + autoware_map_msgs::msg::MapProjectorInfo msg; if (std::filesystem::exists(yaml_filename)) { std::cout << "Load " << yaml_filename << std::endl; @@ -87,7 +96,7 @@ MapProjectionLoader::MapProjectionLoader(const rclcpp::NodeOptions & options) const std::string lanelet2_map_filename = this->declare_parameter("lanelet2_map_path"); - const tier4_map_msgs::msg::MapProjectorInfo msg = + const autoware_map_msgs::msg::MapProjectorInfo msg = load_map_projector_info(yaml_filename, lanelet2_map_filename); // Publish the message diff --git a/map/autoware_map_projection_loader/test/data/map_projector_info_local.yaml b/map/autoware_map_projection_loader/test/data/map_projector_info_local.yaml index 2e5d27c3e8143..b1f30b12d8bde 100644 --- a/map/autoware_map_projection_loader/test/data/map_projector_info_local.yaml +++ b/map/autoware_map_projection_loader/test/data/map_projector_info_local.yaml @@ -1 +1 @@ -projector_type: local +projector_type: Local diff --git a/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp b/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp index 26658e88682a2..f40084ef819c7 100644 --- a/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp +++ b/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp @@ -111,7 +111,7 @@ TEST(TestLoadFromLanelet2Map, LoadLocalGrid) autoware::map_projection_loader::load_info_from_lanelet2_map(output_path); // Check the result - EXPECT_EQ(projector_info.projector_type, "local"); + EXPECT_EQ(projector_info.projector_type, "Local"); } TEST(TestLoadFromLanelet2Map, LoadNoLocalGrid) diff --git a/map/autoware_map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py b/map/autoware_map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py index 495f0092bb01f..30cede4b1ec25 100644 --- a/map/autoware_map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py +++ b/map/autoware_map_projection_loader/test/test_node_load_local_cartesian_utm_from_yaml.test.py @@ -18,6 +18,7 @@ import unittest from ament_index_python import get_package_share_directory +from autoware_map_msgs.msg import MapProjectorInfo import launch from launch import LaunchDescription from launch.logging import get_logger @@ -28,7 +29,6 @@ from rclpy.qos import QoSDurabilityPolicy from rclpy.qos import QoSHistoryPolicy from rclpy.qos import QoSProfile -from tier4_map_msgs.msg import MapProjectorInfo import yaml logger = get_logger(__name__) diff --git a/map/autoware_map_projection_loader/test/test_node_load_local_from_yaml.test.py b/map/autoware_map_projection_loader/test/test_node_load_local_from_yaml.test.py index 8517f09e2006b..9c364f094ee24 100644 --- a/map/autoware_map_projection_loader/test/test_node_load_local_from_yaml.test.py +++ b/map/autoware_map_projection_loader/test/test_node_load_local_from_yaml.test.py @@ -18,6 +18,7 @@ import unittest from ament_index_python import get_package_share_directory +from autoware_map_msgs.msg import MapProjectorInfo import launch from launch import LaunchDescription from launch.logging import get_logger @@ -28,7 +29,6 @@ from rclpy.qos import QoSDurabilityPolicy from rclpy.qos import QoSHistoryPolicy from rclpy.qos import QoSProfile -from tier4_map_msgs.msg import MapProjectorInfo import yaml logger = get_logger(__name__) diff --git a/map/autoware_map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py b/map/autoware_map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py index ad19e61f9f111..6586a9aee98d3 100644 --- a/map/autoware_map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py +++ b/map/autoware_map_projection_loader/test/test_node_load_mgrs_from_yaml.test.py @@ -18,6 +18,7 @@ import unittest from ament_index_python import get_package_share_directory +from autoware_map_msgs.msg import MapProjectorInfo import launch from launch import LaunchDescription from launch.logging import get_logger @@ -28,7 +29,6 @@ from rclpy.qos import QoSDurabilityPolicy from rclpy.qos import QoSHistoryPolicy from rclpy.qos import QoSProfile -from tier4_map_msgs.msg import MapProjectorInfo import yaml logger = get_logger(__name__) diff --git a/map/autoware_map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py b/map/autoware_map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py index ed2eb45535089..3035ce75e692d 100644 --- a/map/autoware_map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py +++ b/map/autoware_map_projection_loader/test/test_node_load_transverse_mercator_from_yaml.test.py @@ -18,6 +18,7 @@ import unittest from ament_index_python import get_package_share_directory +from autoware_map_msgs.msg import MapProjectorInfo import launch from launch import LaunchDescription from launch.logging import get_logger @@ -28,7 +29,6 @@ from rclpy.qos import QoSDurabilityPolicy from rclpy.qos import QoSHistoryPolicy from rclpy.qos import QoSProfile -from tier4_map_msgs.msg import MapProjectorInfo import yaml logger = get_logger(__name__) diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index fb0b821e87644..5375f50c642b7 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -36,7 +36,6 @@ global_parameter_loader rclcpp rclcpp_components - tier4_map_msgs python3-flask-cors rosidl_default_runtime diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp index 17abb3e446994..c591dcfc73bd8 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.hpp @@ -24,10 +24,10 @@ #include "rclcpp/rclcpp.hpp" #include "type_alias.hpp" +#include "autoware_map_msgs/msg/map_projector_info.hpp" #include "std_msgs/msg/empty.hpp" #include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/int32.hpp" -#include "tier4_map_msgs/msg/map_projector_info.hpp" #include #include @@ -36,10 +36,10 @@ namespace autoware::static_centerline_generator { +using autoware_map_msgs::msg::MapProjectorInfo; using autoware_static_centerline_generator::srv::LoadMap; using autoware_static_centerline_generator::srv::PlanPath; using autoware_static_centerline_generator::srv::PlanRoute; -using tier4_map_msgs::msg::MapProjectorInfo; struct CenterlineWithRoute { diff --git a/sensing/autoware_gnss_poser/README.md b/sensing/autoware_gnss_poser/README.md index 9619038492af0..cdd67bde027d2 100644 --- a/sensing/autoware_gnss_poser/README.md +++ b/sensing/autoware_gnss_poser/README.md @@ -17,7 +17,7 @@ If the transformation from `base_link` to the antenna cannot be obtained, it out | Name | Type | Description | | ------------------------------ | ------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------ | -| `/map/map_projector_info` | `tier4_map_msgs::msg::MapProjectorInfo` | map projection info | +| `/map/map_projector_info` | `autoware_map_msgs::msg::MapProjectorInfo` | map projection info | | `~/input/fix` | `sensor_msgs::msg::NavSatFix` | gnss status message | | `~/input/autoware_orientation` | `autoware_sensing_msgs::msg::GnssInsOrientationStamped` | orientation [click here for more details](https://github.com/autowarefoundation/autoware_msgs/tree/main/autoware_sensing_msgs) | diff --git a/simulator/autoware_carla_interface/README.md b/simulator/autoware_carla_interface/README.md index 2513364178693..c98d39bb4f121 100644 --- a/simulator/autoware_carla_interface/README.md +++ b/simulator/autoware_carla_interface/README.md @@ -24,7 +24,7 @@ This ros package enables communication between Autoware and CARLA for autonomous 1. Download maps (y-axis inverted version) to arbitrary location 2. Change names and create the map folder (example: Town01) inside `autoware_map`. (`point_cloud/Town01.pcd` -> `autoware_map/Town01/pointcloud_map.pcd`, `vector_maps/lanelet2/Town01.osm`-> `autoware_map/Town01/lanelet2_map.osm`) -3. Create `map_projector_info.yaml` on the folder and add `projector_type: local` on the first line. +3. Create `map_projector_info.yaml` on the folder and add `projector_type: Local` on the first line. ### Build From 4c0c378acbdaa0f1035a35cdc9b9f76be05594a6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bar=C4=B1=C5=9F=20Zeren?= <76053179+StepTurtle@users.noreply.github.com> Date: Tue, 3 Dec 2024 15:22:13 +0300 Subject: [PATCH 207/273] chore(cspell): add new word `libtensorrt` to `cspell.json` (#9550) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Barış Zeren --- .cspell.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.cspell.json b/.cspell.json index f338e72d194e3..f3bf484f68e0c 100644 --- a/.cspell.json +++ b/.cspell.json @@ -4,5 +4,5 @@ "planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/scripts/**" ], "ignoreRegExpList": [], - "words": ["dltype", "tvmgen", "fromarray", "soblin", "brkay54"] + "words": ["dltype", "tvmgen", "fromarray", "soblin", "brkay54", "libtensorrt"] } From 80f59e7b2804ca371a906c82475cd401168f5f3d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 3 Dec 2024 17:02:17 +0300 Subject: [PATCH 208/273] docs(control_performance_analysis): utilize mathjax syntax in readme (#9552) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../control_performance_analysis/README.md | 50 +++++++++---------- 1 file changed, 25 insertions(+), 25 deletions(-) diff --git a/control/control_performance_analysis/README.md b/control/control_performance_analysis/README.md index 3895b3cc13465..e87efbe179eee 100644 --- a/control/control_performance_analysis/README.md +++ b/control/control_performance_analysis/README.md @@ -44,34 +44,34 @@ Error acceleration calculations are made based on the velocity calculations abov #### control_performance_analysis::msg::DrivingMonitorStamped -| Name | Type | Description | -| ---------------------------- | ----- | -------------------------------------------------------- | -| `longitudinal_acceleration` | float | [m / s^2] | -| `longitudinal_jerk` | float | [m / s^3] | -| `lateral_acceleration` | float | [m / s^2] | -| `lateral_jerk` | float | [m / s^3] | -| `desired_steering_angle` | float | [rad] | -| `controller_processing_time` | float | Timestamp between last two control command messages [ms] | +| Name | Type | Description | +| ---------------------------- | ----- | --------------------------------------------------------------------- | +| `longitudinal_acceleration` | float | $[ \mathrm{m/s^2} ]$ | +| `longitudinal_jerk` | float | $[ \mathrm{m/s^3} ]$ | +| `lateral_acceleration` | float | $[ \mathrm{m/s^2} ]$ | +| `lateral_jerk` | float | $[ \mathrm{m/s^3} ]$ | +| `desired_steering_angle` | float | $[ \mathrm{rad} ]$ | +| `controller_processing_time` | float | Timestamp between last two control command messages $[ \mathrm{ms} ]$ | #### control_performance_analysis::msg::ErrorStamped -| Name | Type | Description | -| ------------------------------------------ | ----- | ----------------------------------------------------------------------------------------------------------------- | -| `lateral_error` | float | [m] | -| `lateral_error_velocity` | float | [m / s] | -| `lateral_error_acceleration` | float | [m / s^2] | -| `longitudinal_error` | float | [m] | -| `longitudinal_error_velocity` | float | [m / s] | -| `longitudinal_error_acceleration` | float | [m / s^2] | -| `heading_error` | float | [rad] | -| `heading_error_velocity` | float | [rad / s] | -| `control_effort_energy` | float | [u * R * u^T] | -| `error_energy` | float | lateral_error^2 + heading_error^2 | -| `value_approximation` | float | V = xPx' ; Value function from DARE Lyap matrix P | -| `curvature_estimate` | float | [1 / m] | -| `curvature_estimate_pp` | float | [1 / m] | -| `vehicle_velocity_error` | float | [m / s] | -| `tracking_curvature_discontinuity_ability` | float | Measures the ability to tracking the curvature changes [`abs(delta(curvature)) / (1 + abs(delta(lateral_error))`] | +| Name | Type | Description | +| ------------------------------------------ | ----- | ----------------------------------------------------------------------------------------------------------------------------------------- | +| `lateral_error` | float | $[ \mathrm{m} ]$ | +| `lateral_error_velocity` | float | $[ \mathrm{m/s} ]$ | +| `lateral_error_acceleration` | float | $[ \mathrm{m/s^2} ]$ | +| `longitudinal_error` | float | $[ \mathrm{m} ]$ | +| `longitudinal_error_velocity` | float | $[ \mathrm{m/s} ]$ | +| `longitudinal_error_acceleration` | float | $[ \mathrm{m/s^2} ]$ | +| `heading_error` | float | $[ \mathrm{rad} ]$ | +| `heading_error_velocity` | float | $[ \mathrm{rad/s} ]$ | +| `control_effort_energy` | float | $[ \mathbf{u}^\top \mathbf{R} \mathbf{u} ]$ simplified to $[ R \cdot u^2 ]$ | +| `error_energy` | float | $e_{\text{lat}}^2 + e_\theta^2$ (squared lateral error + squared heading error) | +| `value_approximation` | float | $V = \mathbf{x}^\top \mathbf{P} \mathbf{x}$; Value function from DARE Lyapunov matrix $\mathbf{P}$ | +| `curvature_estimate` | float | $[ \mathrm{1/m} ]$ | +| `curvature_estimate_pp` | float | $[ \mathrm{1/m} ]$ | +| `vehicle_velocity_error` | float | $[ \mathrm{m/s} ]$ | +| `tracking_curvature_discontinuity_ability` | float | Measures the ability to track curvature changes $\frac{\lvert \Delta(\text{curvature}) \rvert}{1 + \lvert \Delta(e_{\text{lat}}) \rvert}$ | ## Parameters From 31061117d2bd4b444424d58d92f080b9b1adb943 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 3 Dec 2024 20:14:28 +0300 Subject: [PATCH 209/273] docs: update the list styles (#9555) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../README.md | 4 ++-- perception/autoware_radar_object_clustering/README.md | 8 ++++---- planning/autoware_path_optimizer/docs/mpt.md | 6 +++--- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/perception/autoware_radar_crossing_objects_noise_filter/README.md b/perception/autoware_radar_crossing_objects_noise_filter/README.md index 553d932717442..4039624217a5c 100644 --- a/perception/autoware_radar_crossing_objects_noise_filter/README.md +++ b/perception/autoware_radar_crossing_objects_noise_filter/README.md @@ -10,7 +10,7 @@ This package can filter the noise objects which cross to the ego vehicle. This package aim to filter the noise objects which cross from the ego vehicle. The reason why these objects are noise is as below. -- 1. The objects with doppler velocity can be trusted more than those with vertical velocity to it. +#### 1. The objects with doppler velocity can be trusted more than those with vertical velocity to it Radars can get velocity information of objects as doppler velocity, but cannot get vertical velocity to doppler velocity directory. Some radars can output the objects with not only doppler velocity but also vertical velocity by estimation. @@ -22,7 +22,7 @@ Velocity estimation fails on static objects, resulting in ghost objects crossing ![vertical_velocity_objects](docs/vertical_velocity_objects.png) -- 2. Turning around by ego vehicle affect the output from radar. +#### 2. Turning around by ego vehicle affect the output from radar When the ego vehicle turns around, the radars outputting at the object level sometimes fail to estimate the twist of objects correctly even if [radar_tracks_msgs_converter](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/autoware_radar_tracks_msgs_converter) compensates by the ego vehicle twist. So if an object detected by radars has circular motion viewing from base_link, it is likely that the speed is estimated incorrectly and that the object is a static object. diff --git a/perception/autoware_radar_object_clustering/README.md b/perception/autoware_radar_object_clustering/README.md index 0e66208d9f84e..cf52c33eba274 100644 --- a/perception/autoware_radar_object_clustering/README.md +++ b/perception/autoware_radar_object_clustering/README.md @@ -17,12 +17,12 @@ Therefore, by this package the multiple detection results are clustered into one ### Algorithm -- 1. Sort by distance from `base_link` +#### 1. Sort by distance from `base_link` At first, to prevent changing the result from depending on the order of objects in DetectedObjects, input objects are sorted by distance from `base_link`. In addition, to apply matching in closeness order considering occlusion, objects are sorted in order of short distance in advance. -- 2. Clustering +#### 2. Clustering If two radar objects are near, and yaw angle direction and velocity between two radar objects is similar (the degree of these is defined by parameters), then these are clustered. Note that radar characteristic affect parameters for this matching. @@ -32,13 +32,13 @@ For example, if resolution of range distance or angle is low and accuracy of vel After grouping for all radar objects, if multiple radar objects are grouping, the kinematics of the new clustered object is calculated from average of that and label and shape of the new clustered object is calculated from top confidence in radar objects. -- 3. Fixed label correction +#### 3. Fixed label correction When the label information from radar outputs lack accuracy, `is_fixed_label` parameter is recommended to set `true`. If the parameter is true, the label of a clustered object is overwritten by the label set by `fixed_label` parameter. If this package use for faraway dynamic object detection with radar, the parameter is recommended to set to `VEHICLE`. -- 4. Fixed size correction +#### 4. Fixed size correction When the size information from radar outputs lack accuracy, `is_fixed_size` parameter is recommended to set `true`. If the parameter is true, the size of a clustered object is overwritten by the label set by `size_x`, `size_y`, and `size_z` parameters. diff --git a/planning/autoware_path_optimizer/docs/mpt.md b/planning/autoware_path_optimizer/docs/mpt.md index 4b35fd0e36ab5..634542a13295f 100644 --- a/planning/autoware_path_optimizer/docs/mpt.md +++ b/planning/autoware_path_optimizer/docs/mpt.md @@ -360,9 +360,9 @@ $$ To realize collision-free trajectory planning, we have to formulate constraints that the vehicle is inside the road and also does not collide with obstacles in linear equations. For linearity, we implemented some methods to approximate the vehicle shape with a set of circles, that is reliable and easy to implement. -- 1. Bicycle Model -- 2. Uniform Circles -- 3. Fitting Uniform Circles +1. Bicycle Model +2. Uniform Circles +3. Fitting Uniform Circles ![vehicle_circles](../media/vehicle_circles.svg) From de90e599eb8e556fadaf9bc5324270eede9c8864 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 3 Dec 2024 20:50:41 +0300 Subject: [PATCH 210/273] ci(pre-commit): autoupdate (#8949) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: M. Fatih Cırıt --- .pre-commit-config.yaml | 12 ++++++------ .../lib/tracker/motion_model/ctrv_motion_model.cpp | 2 +- .../autoware_surround_obstacle_checker/src/node.cpp | 4 ++-- .../autoware_surround_obstacle_checker/src/node.hpp | 4 ++-- .../test/test_surround_obstacle_checker.cpp | 4 ++-- .../src/utils.cpp | 4 ++-- .../src/utils.hpp | 4 ++-- .../autoware_accel_brake_map_calibrator/README.md | 7 ++++--- 8 files changed, 21 insertions(+), 20 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index e6dcc3f464ac7..f3f3248095a0f 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -7,7 +7,7 @@ ci: repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.6.0 + rev: v5.0.0 hooks: - id: check-json - id: check-merge-conflict @@ -22,7 +22,7 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.41.0 + rev: v0.43.0 hooks: - id: markdownlint args: [-c, .markdownlint.yaml, --fix] @@ -53,7 +53,7 @@ repos: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.9.0-1 + rev: v3.10.0-2 hooks: - id: shfmt args: [-w, -s, -i=4] @@ -64,13 +64,13 @@ repos: - id: isort - repo: https://github.com/psf/black - rev: 24.8.0 + rev: 24.10.0 hooks: - id: black args: [--line-length=100] - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v18.1.8 + rev: v19.1.4 hooks: - id: clang-format types_or: [c++, c, cuda] @@ -83,7 +83,7 @@ repos: exclude: .cu - repo: https://github.com/python-jsonschema/check-jsonschema - rev: 0.29.2 + rev: 0.30.0 hooks: - id: check-metaschema files: ^.+/schema/.*schema\.json$ diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp index 6f63ecbdce06d..700800e94ecd5 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp @@ -276,7 +276,7 @@ bool CTRVMotionModel::predictStateStep(const double dt, KalmanFilter & ekf) cons Eigen::MatrixXd X_next_t(DIM, 1); // predicted state X_next_t(IDX::X) = X_t(IDX::X) + X_t(IDX::VEL) * cos_yaw * dt; // dx = v * cos(yaw) X_next_t(IDX::Y) = X_t(IDX::Y) + X_t(IDX::VEL) * sin_yaw * dt; // dy = v * sin(yaw) - X_next_t(IDX::YAW) = X_t(IDX::YAW) + (X_t(IDX::WZ)) * dt; // dyaw = omega + X_next_t(IDX::YAW) = X_t(IDX::YAW) + (X_t(IDX::WZ))*dt; // dyaw = omega X_next_t(IDX::VEL) = X_t(IDX::VEL); X_next_t(IDX::WZ) = X_t(IDX::WZ); diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index 1a938a9275df5..382281127a113 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -378,8 +378,8 @@ std::optional SurroundObstacleCheckerNode: auto SurroundObstacleCheckerNode::isStopRequired( const bool is_obstacle_found, const bool is_vehicle_stopped, const State & state, - const std::optional & last_obstacle_found_time, - const double time_threshold) const -> std::pair> + const std::optional & last_obstacle_found_time, const double time_threshold) const + -> std::pair> { if (!is_vehicle_stopped) { return std::make_pair(false, std::nullopt); diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index 17eb2979e6809..f84ad3a8f5987 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -89,8 +89,8 @@ class SurroundObstacleCheckerNode : public rclcpp::Node auto isStopRequired( const bool is_obstacle_found, const bool is_vehicle_stopped, const State & state, - const std::optional & last_obstacle_found_time, - const double time_threshold) const -> std::pair>; + const std::optional & last_obstacle_found_time, const double time_threshold) const + -> std::pair>; // ros mutable tf2_ros::Buffer tf_buffer_{get_clock()}; diff --git a/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp b/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp index c5fbb7958208d..1122a37bb2672 100644 --- a/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp +++ b/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp @@ -48,8 +48,8 @@ class SurroundObstacleCheckerNodeTest : public ::testing::Test auto isStopRequired( const bool is_obstacle_found, const bool is_vehicle_stopped, const State & state, - const std::optional & last_obstacle_found_time, - const double time_threshold) const -> std::pair> + const std::optional & last_obstacle_found_time, const double time_threshold) const + -> std::pair> { return node_->isStopRequired( is_obstacle_found, is_vehicle_stopped, state, last_obstacle_found_time, time_threshold); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp index c9eb93abb2e2f..4f0829c901915 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp @@ -32,8 +32,8 @@ auto getOffsetPoint(const Eigen::Vector2d & src, const Eigen::Vector2d & dst, co } auto findNearestCollisionPoint( - const LineString2d & line1, const LineString2d & line2, - const Point2d & origin) -> std::optional + const LineString2d & line1, const LineString2d & line2, const Point2d & origin) + -> std::optional { std::vector collision_points; bg::intersection(line1, line2, collision_points); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.hpp index c6655064d3ffa..ad4ed84cea116 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.hpp @@ -48,8 +48,8 @@ auto getOffsetPoint(const Eigen::Vector2d & src, const Eigen::Vector2d & dst, co * @return intersection point. if there is no intersection point, return std::nullopt. */ auto findNearestCollisionPoint( - const LineString2d & line1, const LineString2d & line2, - const Point2d & origin) -> std::optional; + const LineString2d & line1, const LineString2d & line2, const Point2d & origin) + -> std::optional; /** * @brief find intersection point between path and stop line and return the point. diff --git a/vehicle/autoware_accel_brake_map_calibrator/README.md b/vehicle/autoware_accel_brake_map_calibrator/README.md index 024c8059a169e..a85e7de98a3ef 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/README.md +++ b/vehicle/autoware_accel_brake_map_calibrator/README.md @@ -212,10 +212,11 @@ Update by Recursive Least Squares(RLS) method using data close enough to each gr #### Parameters Data selection is determined by the following thresholds. -| Name | Default Value | + +| Name | Default Value | | ----------------------- | ------------- | -| velocity_diff_threshold | 0.556 | -| pedal_diff_threshold | 0.03 | +| velocity_diff_threshold | 0.556 | +| pedal_diff_threshold | 0.03 | #### Update formula From 8d9ca0ed71f217fdec600b3763a8471d258c70bd Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Wed, 4 Dec 2024 09:43:29 +0900 Subject: [PATCH 211/273] fix(autoware_ground_segmentation): remove unused function (#9536) Signed-off-by: Ryuta Kambe --- .../autoware_ground_segmentation/src/scan_ground_filter/grid.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/grid.hpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid.hpp index 05fcde9317abe..0dbbe1eabb8da 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/grid.hpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid.hpp @@ -114,7 +114,6 @@ class Cell // method to check if the cell is empty inline bool isEmpty() const { return point_list_.empty(); } - inline int getPointNum() const { return static_cast(point_list_.size()); } // index of the cell int grid_idx_; From 8185a5b696042507dd07c126dec877ea4650bbfd Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 4 Dec 2024 14:49:14 +0900 Subject: [PATCH 212/273] refactor(blind_spot): move util functions outside of class (#9544) Signed-off-by: Mamoru Sobue --- .../CMakeLists.txt | 1 + .../scene.hpp | 56 +--- .../util.hpp | 93 ++++++ .../src/manager.cpp | 8 +- .../src/scene.cpp | 315 +----------------- .../src/util.cpp | 314 +++++++++++++++++ 6 files changed, 428 insertions(+), 359 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt index bdaa6d9f6aa2f..b4a688d711221 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CMakeLists.txt @@ -10,6 +10,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/manager.cpp src/scene.cpp src/decisions.cpp + src/util.cpp ) ament_auto_package(INSTALL_TO_SHARE config) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp index e9542feaccfd1..1bfa41d86ffbe 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/scene.hpp @@ -15,17 +15,13 @@ #ifndef AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_ #define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__SCENE_HPP_ +#include #include -#include #include #include -#include #include -#include -#include -#include #include #include @@ -37,21 +33,6 @@ namespace autoware::behavior_velocity_planner { -/** - * @brief wrapper class of interpolated path with lane id - */ -struct InterpolatedPathInfo -{ - /** the interpolated path */ - tier4_planning_msgs::msg::PathWithLaneId path; - /** discretization interval of interpolation */ - double ds{0.0}; - /** the intersection lanelet id */ - lanelet::Id lane_id{0}; - /** the range of indices for the path points with associative lane id */ - std::optional> lane_id_interval{std::nullopt}; -}; - /** * @brief represent action */ @@ -81,8 +62,6 @@ using BlindSpotDecision = std::variant virtual_wall_pose{std::nullopt}; @@ -146,12 +125,6 @@ class BlindSpotModule : public SceneModuleInterface void reactRTCApprovalByDecision( const Decision & decision, tier4_planning_msgs::msg::PathWithLaneId * path); - std::optional generateInterpolatedPathInfo( - const tier4_planning_msgs::msg::PathWithLaneId & input_path) const; - - std::optional getSiblingStraightLanelet( - const std::shared_ptr planner_data) const; - /** * @brief Generate a stop line and insert it into the path. * A stop line is at an intersection point of straight path with vehicle path @@ -188,33 +161,6 @@ class BlindSpotModule : public SceneModuleInterface const geometry_msgs::msg::Pose & stop_line_pose, const lanelet::CompoundPolygon3d & area, const double ego_time_to_reach_stop_line); - /** - * @brief Create half lanelet - * @param lanelet input lanelet - * @return Half lanelet - */ - lanelet::ConstLanelet generateHalfLanelet(const lanelet::ConstLanelet lanelet) const; - - lanelet::ConstLanelet generateExtendedAdjacentLanelet( - const lanelet::ConstLanelet lanelet, const TurnDirection direction) const; - lanelet::ConstLanelet generateExtendedOppositeAdjacentLanelet( - const lanelet::ConstLanelet lanelet, const TurnDirection direction) const; - - lanelet::ConstLanelets generateBlindSpotLanelets( - const tier4_planning_msgs::msg::PathWithLaneId & path) const; - - /** - * @brief Make blind spot areas. Narrow area is made from closest path point to stop line index. - * Broad area is made from backward expanded point to stop line point - * @param path path information associated with lane id - * @param closest_idx closest path point index from ego car in path points - * @return Blind spot polygons - */ - std::optional generateBlindSpotPolygons( - const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, - const lanelet::ConstLanelets & blind_spot_lanelets, - const geometry_msgs::msg::Pose & stop_line_pose) const; - /** * @brief Check if object is belong to targeted classes * @param object Dynamic object diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp new file mode 100644 index 0000000000000..9d908414b6d95 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/include/autoware/behavior_velocity_blind_spot_module/util.hpp @@ -0,0 +1,93 @@ +// 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_VELOCITY_BLIND_SPOT_MODULE__UTIL_HPP_ +#define AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__UTIL_HPP_ + +#include + +#include + +#include +#include + +#include +#include +#include + +namespace autoware::behavior_velocity_planner +{ + +enum class TurnDirection { LEFT, RIGHT }; + +/** + * @brief wrapper class of interpolated path with lane id + */ +struct InterpolatedPathInfo +{ + /** the interpolated path */ + tier4_planning_msgs::msg::PathWithLaneId path; + /** discretization interval of interpolation */ + double ds{0.0}; + /** the intersection lanelet id */ + lanelet::Id lane_id{0}; + /** the range of indices for the path points with associative lane id */ + std::optional> lane_id_interval{std::nullopt}; +}; + +std::optional generateInterpolatedPathInfo( + const lanelet::Id lane_id, const tier4_planning_msgs::msg::PathWithLaneId & input_path, + rclcpp::Logger logger); + +std::optional getSiblingStraightLanelet( + const lanelet::Lanelet assigned_lane, + const lanelet::routing::RoutingGraphConstPtr routing_graph_ptr); + +/** + * @brief Create half lanelet + * @param lanelet input lanelet + * @return Half lanelet + */ +lanelet::ConstLanelet generateHalfLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection & turn_direction, + const double ignore_width_from_centerline); + +lanelet::ConstLanelet generateExtendedAdjacentLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection direction, + const double adjacent_extend_width); +lanelet::ConstLanelet generateExtendedOppositeAdjacentLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection direction, + const double opposite_adjacent_extend_width); + +lanelet::ConstLanelets generateBlindSpotLanelets( + const std::shared_ptr route_handler, + const TurnDirection turn_direction, const lanelet::Id lane_id, + const tier4_planning_msgs::msg::PathWithLaneId & path, const double ignore_width_from_centerline, + const double adjacent_extend_width, const double opposite_adjacent_extend_width); + +/** + * @brief Make blind spot areas. Narrow area is made from closest path point to stop line index. + * Broad area is made from backward expanded point to stop line point + * @param path path information associated with lane id + * @param closest_idx closest path point index from ego car in path points + * @return Blind spot polygons + */ +std::optional generateBlindSpotPolygons( + const tier4_planning_msgs::msg::PathWithLaneId & path, const size_t closest_idx, + const lanelet::ConstLanelets & blind_spot_lanelets, + const geometry_msgs::msg::Pose & stop_line_pose, const double backward_detection_length); + +} // namespace autoware::behavior_velocity_planner + +#endif // AUTOWARE__BEHAVIOR_VELOCITY_BLIND_SPOT_MODULE__UTIL_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp index 5e05de72e0cab..cc63b42df68e4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/manager.cpp @@ -14,6 +14,8 @@ #include "autoware/behavior_velocity_blind_spot_module/manager.hpp" +#include "autoware/behavior_velocity_blind_spot_module/util.hpp" + #include #include @@ -23,7 +25,6 @@ #include #include #include -#include namespace autoware::behavior_velocity_planner { @@ -69,9 +70,8 @@ void BlindSpotModuleManager::launchNewModules(const tier4_planning_msgs::msg::Pa if (turn_direction_str != "left" && turn_direction_str != "right") { continue; } - const auto turn_direction = turn_direction_str == "left" - ? BlindSpotModule::TurnDirection::LEFT - : BlindSpotModule::TurnDirection::RIGHT; + const auto turn_direction = + turn_direction_str == "left" ? TurnDirection::LEFT : TurnDirection::RIGHT; registerModule(std::make_shared( module_id, lane_id, turn_direction, planner_data_, planner_param_, diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp index b5cbbfdf354bb..7697786adb19d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp @@ -14,29 +14,22 @@ #include "autoware/behavior_velocity_blind_spot_module/scene.hpp" +#include "autoware/behavior_velocity_blind_spot_module/util.hpp" + #include -#include #include #include -#include -#include #include -#include -#include -#include -#include +#include -#include #include -#include #include #include #include #include #include -#include #include #include @@ -55,7 +48,9 @@ BlindSpotModule::BlindSpotModule( is_over_pass_judge_line_(false) { velocity_factor_.init(PlanningBehavior::REAR_CHECK); - sibling_straight_lanelet_ = getSiblingStraightLanelet(planner_data); + sibling_straight_lanelet_ = getSiblingStraightLanelet( + planner_data->route_handler_->getLaneletMapPtr()->laneletLayer.get(lane_id_), + planner_data->route_handler_->getRoutingGraphPtr()); } void BlindSpotModule::initializeRTCStatus() @@ -72,7 +67,8 @@ BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail(PathWithLaneId * pat const auto & input_path = *path; /* set stop-line and stop-judgement-line for base_link */ - const auto interpolated_path_info_opt = generateInterpolatedPathInfo(input_path); + const auto interpolated_path_info_opt = + generateInterpolatedPathInfo(lane_id_, input_path, logger_); if (!interpolated_path_info_opt) { return InternalError{"Failed to interpolate path"}; } @@ -105,7 +101,10 @@ BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail(PathWithLaneId * pat } if (!blind_spot_lanelets_) { - const auto blind_spot_lanelets = generateBlindSpotLanelets(input_path); + const auto blind_spot_lanelets = generateBlindSpotLanelets( + planner_data_->route_handler_, turn_direction_, lane_id_, input_path, + planner_param_.ignore_width_from_center_line, planner_param_.adjacent_extend_width, + planner_param_.opposite_adjacent_extend_width); if (!blind_spot_lanelets.empty()) { blind_spot_lanelets_ = blind_spot_lanelets; } @@ -116,8 +115,8 @@ BlindSpotDecision BlindSpotModule::modifyPathVelocityDetail(PathWithLaneId * pat const auto & blind_spot_lanelets = blind_spot_lanelets_.value(); const auto detection_area_opt = generateBlindSpotPolygons( - input_path, closest_idx, blind_spot_lanelets, - path->points.at(critical_stopline_idx).point.pose); + input_path, closest_idx, blind_spot_lanelets, path->points.at(critical_stopline_idx).point.pose, + planner_param_.backward_detection_length); if (!detection_area_opt) { return InternalError{"Failed to generate BlindSpotPolygons"}; } @@ -180,76 +179,6 @@ bool BlindSpotModule::modifyPathVelocity(PathWithLaneId * path) return true; } -static bool hasLaneIds( - const tier4_planning_msgs::msg::PathPointWithLaneId & p, const lanelet::Id id) -{ - for (const auto & pid : p.lane_ids) { - if (pid == id) { - return true; - } - } - return false; -} - -static std::optional> findLaneIdInterval( - const tier4_planning_msgs::msg::PathWithLaneId & p, const lanelet::Id id) -{ - bool found = false; - size_t start = 0; - size_t end = p.points.size() > 0 ? p.points.size() - 1 : 0; - if (start == end) { - // there is only one point in the path - return std::nullopt; - } - for (size_t i = 0; i < p.points.size(); ++i) { - if (hasLaneIds(p.points.at(i), id)) { - if (!found) { - // found interval for the first time - found = true; - start = i; - } - } else if (found) { - // prior point was in the interval. interval ended - end = i; - break; - } - } - start = start > 0 ? start - 1 : 0; // the idx of last point before the interval - return found ? std::make_optional(std::make_pair(start, end)) : std::nullopt; -} - -std::optional BlindSpotModule::generateInterpolatedPathInfo( - const tier4_planning_msgs::msg::PathWithLaneId & input_path) const -{ - constexpr double ds = 0.2; - InterpolatedPathInfo interpolated_path_info; - if (!splineInterpolate(input_path, ds, interpolated_path_info.path, logger_)) { - return std::nullopt; - } - interpolated_path_info.ds = ds; - interpolated_path_info.lane_id = lane_id_; - interpolated_path_info.lane_id_interval = - findLaneIdInterval(interpolated_path_info.path, lane_id_); - return interpolated_path_info; -} - -std::optional BlindSpotModule::getSiblingStraightLanelet( - const std::shared_ptr planner_data) const -{ - const auto lanelet_map_ptr = planner_data->route_handler_->getLaneletMapPtr(); - const auto routing_graph_ptr = planner_data->route_handler_->getRoutingGraphPtr(); - - const auto assigned_lane = lanelet_map_ptr->laneletLayer.get(lane_id_); - for (const auto & prev : routing_graph_ptr->previous(assigned_lane)) { - for (const auto & following : routing_graph_ptr->following(prev)) { - if (std::string(following.attributeOr("turn_direction", "else")) == "straight") { - return following; - } - } - } - return std::nullopt; -} - static std::optional getFirstPointIntersectsLineByFootprint( const lanelet::ConstLineString2d & line, const InterpolatedPathInfo & interpolated_path_info, const autoware::universe_utils::LinearRing2d & footprint, const double vehicle_length) @@ -441,7 +370,7 @@ double BlindSpotModule::computeTimeToPassStopLine( const lanelet::ConstLanelets & blind_spot_lanelets, const geometry_msgs::msg::Pose & stop_line_pose) const { - // egoが停止している時にそのまま速度を使うと衝突しなくなってしまうのでegoについては最低速度を使う + // if ego is completely stopped, using ego velocity yields "no-collision" const auto & current_pose = planner_data_->current_odometry->pose; const auto current_arc_ego = lanelet::utils::getArcCoordinates(blind_spot_lanelets, current_pose).length; @@ -491,220 +420,6 @@ std::optional BlindSpotModule::i return std::nullopt; } -lanelet::ConstLanelet BlindSpotModule::generateHalfLanelet( - const lanelet::ConstLanelet lanelet) const -{ - lanelet::Points3d lefts, rights; - - const double offset = (turn_direction_ == TurnDirection::LEFT) - ? planner_param_.ignore_width_from_center_line - : -planner_param_.ignore_width_from_center_line; - const auto offset_centerline = lanelet::utils::getCenterlineWithOffset(lanelet, offset); - - const auto original_left_bound = - (turn_direction_ == TurnDirection::LEFT) ? lanelet.leftBound() : offset_centerline; - const auto original_right_bound = - (turn_direction_ == TurnDirection::LEFT) ? offset_centerline : lanelet.rightBound(); - - for (const auto & pt : original_left_bound) { - lefts.push_back(lanelet::Point3d(pt)); - } - for (const auto & pt : original_right_bound) { - rights.push_back(lanelet::Point3d(pt)); - } - const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); - const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); - auto half_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); - return half_lanelet; -} - -lanelet::ConstLanelet BlindSpotModule::generateExtendedAdjacentLanelet( - const lanelet::ConstLanelet lanelet, const TurnDirection direction) const -{ - const auto centerline = lanelet.centerline2d(); - const auto width = - boost::geometry::area(lanelet.polygon2d().basicPolygon()) / boost::geometry::length(centerline); - const double extend_width = std::min(planner_param_.adjacent_extend_width, width); - const auto left_bound_ = - direction == TurnDirection::LEFT - ? lanelet::utils::getCenterlineWithOffset(lanelet, -width / 2 + extend_width) - : lanelet.leftBound(); - const auto right_bound_ = - direction == TurnDirection::RIGHT - ? lanelet::utils::getCenterlineWithOffset(lanelet, width / 2 - extend_width) - : lanelet.rightBound(); - lanelet::Points3d lefts, rights; - for (const auto & pt : left_bound_) { - lefts.push_back(lanelet::Point3d(pt)); - } - for (const auto & pt : right_bound_) { - rights.push_back(lanelet::Point3d(pt)); - } - const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); - const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); - auto new_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); - const auto new_centerline = lanelet::utils::generateFineCenterline(new_lanelet, 5.0); - new_lanelet.setCenterline(new_centerline); - return new_lanelet; -} - -lanelet::ConstLanelet BlindSpotModule::generateExtendedOppositeAdjacentLanelet( - const lanelet::ConstLanelet lanelet, const TurnDirection direction) const -{ - const auto centerline = lanelet.centerline2d(); - const auto width = - boost::geometry::area(lanelet.polygon2d().basicPolygon()) / boost::geometry::length(centerline); - const double extend_width = - std::min(planner_param_.opposite_adjacent_extend_width, width); - const auto left_bound_ = - direction == TurnDirection::RIGHT - ? lanelet.rightBound().invert() - : lanelet::utils::getCenterlineWithOffset(lanelet.invert(), -width / 2 + extend_width); - const auto right_bound_ = - direction == TurnDirection::RIGHT - ? lanelet::utils::getCenterlineWithOffset(lanelet.invert(), width / 2 - extend_width) - : lanelet.leftBound().invert(); - lanelet::Points3d lefts, rights; - for (const auto & pt : left_bound_) { - lefts.push_back(lanelet::Point3d(pt)); - } - for (const auto & pt : right_bound_) { - rights.push_back(lanelet::Point3d(pt)); - } - const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); - const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); - auto new_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); - const auto new_centerline = lanelet::utils::generateFineCenterline(new_lanelet, 5.0); - new_lanelet.setCenterline(new_centerline); - return new_lanelet; -} - -static lanelet::LineString3d removeConst(lanelet::ConstLineString3d line) -{ - lanelet::Points3d pts; - for (const auto & pt : line) { - pts.push_back(lanelet::Point3d(pt)); - } - return lanelet::LineString3d(lanelet::InvalId, pts); -} - -lanelet::ConstLanelets BlindSpotModule::generateBlindSpotLanelets( - const tier4_planning_msgs::msg::PathWithLaneId & path) const -{ - /* get lanelet map */ - const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr(); - const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr(); - - std::vector lane_ids; - /* get lane ids until intersection */ - for (const auto & point : path.points) { - bool found_intersection_lane = false; - for (const auto lane_id : point.lane_ids) { - if (lane_id == lane_id_) { - found_intersection_lane = true; - lane_ids.push_back(lane_id); - break; - } - // make lane_ids unique - if (std::find(lane_ids.begin(), lane_ids.end(), lane_id) == lane_ids.end()) { - lane_ids.push_back(lane_id); - } - } - if (found_intersection_lane) break; - } - - lanelet::ConstLanelets blind_spot_lanelets; - for (const auto i : lane_ids) { - const auto lane = lanelet_map_ptr->laneletLayer.get(i); - const auto ego_half_lanelet = generateHalfLanelet(lane); - const auto assoc_adj = - turn_direction_ == TurnDirection::LEFT - ? (routing_graph_ptr->adjacentLeft(lane)) - : (turn_direction_ == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight(lane)) - : boost::none); - const std::optional opposite_adj = - [&]() -> std::optional { - if (!!assoc_adj) { - return std::nullopt; - } - if (turn_direction_ == TurnDirection::LEFT) { - // this should exist in right-hand traffic - const auto adjacent_lanes = - lanelet_map_ptr->laneletLayer.findUsages(lane.leftBound().invert()); - if (adjacent_lanes.empty()) { - return std::nullopt; - } - return adjacent_lanes.front(); - } - if (turn_direction_ == TurnDirection::RIGHT) { - // this should exist in left-hand traffic - const auto adjacent_lanes = - lanelet_map_ptr->laneletLayer.findUsages(lane.rightBound().invert()); - if (adjacent_lanes.empty()) { - return std::nullopt; - } - return adjacent_lanes.front(); - } else { - return std::nullopt; - } - }(); - - const auto assoc_shoulder = [&]() -> std::optional { - if (turn_direction_ == TurnDirection::LEFT) { - return planner_data_->route_handler_->getLeftShoulderLanelet(lane); - } else if (turn_direction_ == TurnDirection::RIGHT) { - return planner_data_->route_handler_->getRightShoulderLanelet(lane); - } - return std::nullopt; - }(); - if (assoc_shoulder) { - const auto lefts = (turn_direction_ == TurnDirection::LEFT) - ? assoc_shoulder.value().leftBound() - : ego_half_lanelet.leftBound(); - const auto rights = (turn_direction_ == TurnDirection::LEFT) - ? ego_half_lanelet.rightBound() - : assoc_shoulder.value().rightBound(); - blind_spot_lanelets.push_back( - lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights))); - - } else if (!!assoc_adj) { - const auto adj_half_lanelet = - generateExtendedAdjacentLanelet(assoc_adj.value(), turn_direction_); - const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound() - : ego_half_lanelet.leftBound(); - const auto rights = (turn_direction_ == TurnDirection::RIGHT) ? adj_half_lanelet.rightBound() - : ego_half_lanelet.rightBound(); - blind_spot_lanelets.push_back( - lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights))); - } else if (opposite_adj) { - const auto adj_half_lanelet = - generateExtendedOppositeAdjacentLanelet(opposite_adj.value(), turn_direction_); - const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound() - : ego_half_lanelet.leftBound(); - const auto rights = (turn_direction_ == TurnDirection::LEFT) ? ego_half_lanelet.rightBound() - : adj_half_lanelet.rightBound(); - blind_spot_lanelets.push_back( - lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights))); - } else { - blind_spot_lanelets.push_back(ego_half_lanelet); - } - } - return blind_spot_lanelets; -} - -std::optional BlindSpotModule::generateBlindSpotPolygons( - [[maybe_unused]] const tier4_planning_msgs::msg::PathWithLaneId & path, - [[maybe_unused]] const size_t closest_idx, const lanelet::ConstLanelets & blind_spot_lanelets, - const geometry_msgs::msg::Pose & stop_line_pose) const -{ - const auto stop_line_arc_ego = - lanelet::utils::getArcCoordinates(blind_spot_lanelets, stop_line_pose).length; - const auto detection_area_start_length_ego = - std::max(stop_line_arc_ego - planner_param_.backward_detection_length, 0.0); - return lanelet::utils::getPolygonFromArcLength( - blind_spot_lanelets, detection_area_start_length_ego, stop_line_arc_ego); -} - bool BlindSpotModule::isTargetObjectType( const autoware_perception_msgs::msg::PredictedObject & object) const { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp new file mode 100644 index 0000000000000..fde6202c7ce24 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp @@ -0,0 +1,314 @@ +// 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 +#include + +#include +#include +#include + +#include + +namespace autoware::behavior_velocity_planner +{ + +namespace +{ +static bool hasLaneIds( + const tier4_planning_msgs::msg::PathPointWithLaneId & p, const lanelet::Id id) +{ + for (const auto & pid : p.lane_ids) { + if (pid == id) { + return true; + } + } + return false; +} + +static std::optional> findLaneIdInterval( + const tier4_planning_msgs::msg::PathWithLaneId & p, const lanelet::Id id) +{ + bool found = false; + size_t start = 0; + size_t end = p.points.size() > 0 ? p.points.size() - 1 : 0; + if (start == end) { + // there is only one point in the path + return std::nullopt; + } + for (size_t i = 0; i < p.points.size(); ++i) { + if (hasLaneIds(p.points.at(i), id)) { + if (!found) { + // found interval for the first time + found = true; + start = i; + } + } else if (found) { + // prior point was in the interval. interval ended + end = i; + break; + } + } + start = start > 0 ? start - 1 : 0; // the idx of last point before the interval + return found ? std::make_optional(std::make_pair(start, end)) : std::nullopt; +} +} // namespace + +std::optional generateInterpolatedPathInfo( + const lanelet::Id lane_id, const tier4_planning_msgs::msg::PathWithLaneId & input_path, + rclcpp::Logger logger) +{ + constexpr double ds = 0.2; + InterpolatedPathInfo interpolated_path_info; + if (!splineInterpolate(input_path, ds, interpolated_path_info.path, logger)) { + return std::nullopt; + } + interpolated_path_info.ds = ds; + interpolated_path_info.lane_id = lane_id; + interpolated_path_info.lane_id_interval = + findLaneIdInterval(interpolated_path_info.path, lane_id); + return interpolated_path_info; +} + +std::optional getSiblingStraightLanelet( + const lanelet::Lanelet assigned_lane, + const lanelet::routing::RoutingGraphConstPtr routing_graph_ptr) +{ + for (const auto & prev : routing_graph_ptr->previous(assigned_lane)) { + for (const auto & following : routing_graph_ptr->following(prev)) { + if (std::string(following.attributeOr("turn_direction", "else")) == "straight") { + return following; + } + } + } + return std::nullopt; +} + +lanelet::ConstLanelet generateHalfLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection & turn_direction, + const double ignore_width_from_centerline) +{ + lanelet::Points3d lefts, rights; + + const double offset = (turn_direction == TurnDirection::LEFT) ? ignore_width_from_centerline + : -ignore_width_from_centerline; + const auto offset_centerline = lanelet::utils::getCenterlineWithOffset(lanelet, offset); + + const auto original_left_bound = + (turn_direction == TurnDirection::LEFT) ? lanelet.leftBound() : offset_centerline; + const auto original_right_bound = + (turn_direction == TurnDirection::LEFT) ? offset_centerline : lanelet.rightBound(); + + for (const auto & pt : original_left_bound) { + lefts.emplace_back(pt); + } + for (const auto & pt : original_right_bound) { + rights.emplace_back(pt); + } + const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); + const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); + auto half_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); + return half_lanelet; +} + +lanelet::ConstLanelet generateExtendedAdjacentLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection direction, + const double adjacent_extend_width) +{ + const auto centerline = lanelet.centerline2d(); + const auto width = + boost::geometry::area(lanelet.polygon2d().basicPolygon()) / boost::geometry::length(centerline); + const double extend_width = std::min(adjacent_extend_width, width); + const auto left_bound_ = + direction == TurnDirection::LEFT + ? lanelet::utils::getCenterlineWithOffset(lanelet, -width / 2 + extend_width) + : lanelet.leftBound(); + const auto right_bound_ = + direction == TurnDirection::RIGHT + ? lanelet::utils::getCenterlineWithOffset(lanelet, width / 2 - extend_width) + : lanelet.rightBound(); + lanelet::Points3d lefts, rights; + for (const auto & pt : left_bound_) { + lefts.emplace_back(pt); + } + for (const auto & pt : right_bound_) { + rights.emplace_back(pt); + } + const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); + const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); + auto new_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); + const auto new_centerline = lanelet::utils::generateFineCenterline(new_lanelet, 5.0); + new_lanelet.setCenterline(new_centerline); + return new_lanelet; +} + +lanelet::ConstLanelet generateExtendedOppositeAdjacentLanelet( + const lanelet::ConstLanelet lanelet, const TurnDirection direction, + const double opposite_adjacent_extend_width) +{ + const auto centerline = lanelet.centerline2d(); + const auto width = + boost::geometry::area(lanelet.polygon2d().basicPolygon()) / boost::geometry::length(centerline); + const double extend_width = std::min(opposite_adjacent_extend_width, width); + const auto left_bound_ = + direction == TurnDirection::RIGHT + ? lanelet.rightBound().invert() + : lanelet::utils::getCenterlineWithOffset(lanelet.invert(), -width / 2 + extend_width); + const auto right_bound_ = + direction == TurnDirection::RIGHT + ? lanelet::utils::getCenterlineWithOffset(lanelet.invert(), width / 2 - extend_width) + : lanelet.leftBound().invert(); + lanelet::Points3d lefts, rights; + for (const auto & pt : left_bound_) { + lefts.emplace_back(pt); + } + for (const auto & pt : right_bound_) { + rights.emplace_back(pt); + } + const auto left_bound = lanelet::LineString3d(lanelet::InvalId, std::move(lefts)); + const auto right_bound = lanelet::LineString3d(lanelet::InvalId, std::move(rights)); + auto new_lanelet = lanelet::Lanelet(lanelet::InvalId, left_bound, right_bound); + const auto new_centerline = lanelet::utils::generateFineCenterline(new_lanelet, 5.0); + new_lanelet.setCenterline(new_centerline); + return new_lanelet; +} + +static lanelet::LineString3d removeConst(lanelet::ConstLineString3d line) +{ + lanelet::Points3d pts; + for (const auto & pt : line) { + pts.emplace_back(pt); + } + return lanelet::LineString3d(lanelet::InvalId, pts); +} + +lanelet::ConstLanelets generateBlindSpotLanelets( + const std::shared_ptr route_handler, + const TurnDirection turn_direction, const lanelet::Id lane_id, + const tier4_planning_msgs::msg::PathWithLaneId & path, const double ignore_width_from_centerline, + const double adjacent_extend_width, const double opposite_adjacent_extend_width) +{ + const auto lanelet_map_ptr = route_handler->getLaneletMapPtr(); + const auto routing_graph_ptr = route_handler->getRoutingGraphPtr(); + + std::vector lane_ids; + /* get lane ids until intersection */ + for (const auto & point : path.points) { + bool found_intersection_lane = false; + for (const auto id : point.lane_ids) { + if (id == lane_id) { + found_intersection_lane = true; + lane_ids.push_back(lane_id); + break; + } + // make lane_ids unique + if (std::find(lane_ids.begin(), lane_ids.end(), lane_id) == lane_ids.end()) { + lane_ids.push_back(lane_id); + } + } + if (found_intersection_lane) break; + } + + lanelet::ConstLanelets blind_spot_lanelets; + for (const auto i : lane_ids) { + const auto lane = lanelet_map_ptr->laneletLayer.get(i); + const auto ego_half_lanelet = + generateHalfLanelet(lane, turn_direction, ignore_width_from_centerline); + const auto assoc_adj = + turn_direction == TurnDirection::LEFT + ? (routing_graph_ptr->adjacentLeft(lane)) + : (turn_direction == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight(lane)) + : boost::none); + const std::optional opposite_adj = + [&]() -> std::optional { + if (!!assoc_adj) { + return std::nullopt; + } + if (turn_direction == TurnDirection::LEFT) { + // this should exist in right-hand traffic + const auto adjacent_lanes = + lanelet_map_ptr->laneletLayer.findUsages(lane.leftBound().invert()); + if (adjacent_lanes.empty()) { + return std::nullopt; + } + return adjacent_lanes.front(); + } + if (turn_direction == TurnDirection::RIGHT) { + // this should exist in left-hand traffic + const auto adjacent_lanes = + lanelet_map_ptr->laneletLayer.findUsages(lane.rightBound().invert()); + if (adjacent_lanes.empty()) { + return std::nullopt; + } + return adjacent_lanes.front(); + } else { + return std::nullopt; + } + }(); + + const auto assoc_shoulder = [&]() -> std::optional { + if (turn_direction == TurnDirection::LEFT) { + return route_handler->getLeftShoulderLanelet(lane); + } else if (turn_direction == TurnDirection::RIGHT) { + return route_handler->getRightShoulderLanelet(lane); + } + return std::nullopt; + }(); + if (assoc_shoulder) { + const auto lefts = (turn_direction == TurnDirection::LEFT) + ? assoc_shoulder.value().leftBound() + : ego_half_lanelet.leftBound(); + const auto rights = (turn_direction == TurnDirection::LEFT) + ? ego_half_lanelet.rightBound() + : assoc_shoulder.value().rightBound(); + blind_spot_lanelets.emplace_back(lanelet::InvalId, removeConst(lefts), removeConst(rights)); + + } else if (!!assoc_adj) { + const auto adj_half_lanelet = + generateExtendedAdjacentLanelet(assoc_adj.value(), turn_direction, adjacent_extend_width); + const auto lefts = (turn_direction == TurnDirection::LEFT) ? adj_half_lanelet.leftBound() + : ego_half_lanelet.leftBound(); + const auto rights = (turn_direction == TurnDirection::RIGHT) ? adj_half_lanelet.rightBound() + : ego_half_lanelet.rightBound(); + blind_spot_lanelets.emplace_back(lanelet::InvalId, removeConst(lefts), removeConst(rights)); + } else if (opposite_adj) { + const auto adj_half_lanelet = generateExtendedOppositeAdjacentLanelet( + opposite_adj.value(), turn_direction, opposite_adjacent_extend_width); + const auto lefts = (turn_direction == TurnDirection::LEFT) ? adj_half_lanelet.leftBound() + : ego_half_lanelet.leftBound(); + const auto rights = (turn_direction == TurnDirection::LEFT) ? ego_half_lanelet.rightBound() + : adj_half_lanelet.rightBound(); + blind_spot_lanelets.emplace_back(lanelet::InvalId, removeConst(lefts), removeConst(rights)); + } else { + blind_spot_lanelets.push_back(ego_half_lanelet); + } + } + return blind_spot_lanelets; +} + +std::optional generateBlindSpotPolygons( + [[maybe_unused]] const tier4_planning_msgs::msg::PathWithLaneId & path, + [[maybe_unused]] const size_t closest_idx, const lanelet::ConstLanelets & blind_spot_lanelets, + const geometry_msgs::msg::Pose & stop_line_pose, const double backward_detection_length) +{ + const auto stop_line_arc_ego = + lanelet::utils::getArcCoordinates(blind_spot_lanelets, stop_line_pose).length; + const auto detection_area_start_length_ego = + std::max(stop_line_arc_ego - backward_detection_length, 0.0); + return lanelet::utils::getPolygonFromArcLength( + blind_spot_lanelets, detection_area_start_length_ego, stop_line_arc_ego); +} + +} // namespace autoware::behavior_velocity_planner From 560654fb033cf264fc369cdd6881034f217c4817 Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Wed, 4 Dec 2024 15:51:56 +0900 Subject: [PATCH 213/273] fix(autoware_map_based_prediction): msg namespace (#9553) Signed-off-by: amadeuszsz --- .../src/map_based_prediction_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) 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 4c4b7b30caecf..e2ccae19a04f7 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 @@ -691,7 +691,7 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object) if ( object.kinematics.orientation_availability == - autoware_perception_msgs::msg::DetectedObjectKinematics::AVAILABLE) { + autoware_perception_msgs::msg::TrackedObjectKinematics::AVAILABLE) { return; } @@ -712,7 +712,7 @@ void MapBasedPredictionNode::updateObjectData(TrackedObject & object) if (abs_object_speed < min_abs_speed) return; switch (object.kinematics.orientation_availability) { - case autoware_perception_msgs::msg::DetectedObjectKinematics::SIGN_UNKNOWN: { + case autoware_perception_msgs::msg::TrackedObjectKinematics::SIGN_UNKNOWN: { const auto original_yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); // flip the angle From 3a749cc31fb5f6e838f46fe8c706488becbc4cac Mon Sep 17 00:00:00 2001 From: Kenzo Lobos Tsunekawa Date: Wed, 4 Dec 2024 17:12:37 +0900 Subject: [PATCH 214/273] chore(autoware_lidar_transfusion): added a warning if we are dropping voxels (#9486) * chore: added a warning if we are dropping voxels Signed-off-by: Kenzo Lobos-Tsunekawa * chore: changed the warning to a throttled one Signed-off-by: Kenzo Lobos-Tsunekawa --------- Signed-off-by: Kenzo Lobos-Tsunekawa --- .../autoware_lidar_transfusion/lib/transfusion_trt.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp index 42e017a2dfdda..09702099f001e 100644 --- a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp +++ b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp @@ -175,6 +175,13 @@ bool TransfusionTRT::preprocess( } if (params_input > config_.max_voxels_) { + rclcpp::Clock clock{RCL_ROS_TIME}; + RCLCPP_WARN_THROTTLE( + rclcpp::get_logger("lidar_transfusion"), clock, 1000, + "The actual number of voxels (%u) exceeds its maximum value (%zu). " + "Please considering increasing it since it may limit the detection performance.", + params_input, config_.max_voxels_); + params_input = config_.max_voxels_; } RCLCPP_DEBUG_STREAM( From 42cc37fbfbab515bf6a06aebd3fc204d27c0f98c Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Wed, 4 Dec 2024 18:49:24 +0900 Subject: [PATCH 215/273] feat(build-and-test-differential): if unnecessary, completely ignore cuda build (#9520) Signed-off-by: Y.Hisaki --- .../build-and-test-differential.yaml | 133 ++++++++++++++---- 1 file changed, 103 insertions(+), 30 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 540ab64b4f279..f62904b03c6e4 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -27,29 +27,58 @@ jobs: with: label: tag:require-cuda-build-and-test - build-and-test-differential: + prepare-build-and-test-differential: + runs-on: ubuntu-latest needs: [make-sure-label-is-present, make-sure-require-cuda-label-is-present] - if: ${{ needs.make-sure-label-is-present.outputs.result == 'true' }} - runs-on: ${{ matrix.runner }} - container: ${{ matrix.container }}${{ matrix.container-suffix }} - strategy: - fail-fast: false - matrix: - rosdistro: - - humble - container-suffix: - - "" - - -cuda - include: - - rosdistro: humble - container: ghcr.io/autowarefoundation/autoware:universe-devel - build-depends-repos: build_depends.repos - - container-suffix: -cuda - runner: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large - build-pre-command: taskset --cpu-list 0-5 - - container-suffix: "" - runner: ubuntu-latest - build-pre-command: "" + outputs: + cuda_build: ${{ steps.check-if-cuda-build-is-required.outputs.cuda_build }} + steps: + - name: Check if cuda-build is required + id: check-if-cuda-build-is-required + run: | + if ${{ needs.make-sure-require-cuda-label-is-present.outputs.result == 'true' }}; then + echo "cuda-build is required" + echo "cuda_build=true" >> $GITHUB_OUTPUT + else + echo "cuda-build is not required" + echo "cuda_build=false" >> $GITHUB_OUTPUT + fi + shell: bash + - name: Fail if the tag:run-build-and-test-differential is missing + if: ${{ needs.make-sure-label-is-present.outputs.result != 'true' }} + run: exit 1 + + build-and-test-differential: + runs-on: ubuntu-latest + container: ghcr.io/autowarefoundation/autoware:universe-devel + needs: prepare-build-and-test-differential + steps: + - name: Set PR fetch depth + run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" + shell: bash + + - name: Checkout PR branch and all PR commits + uses: actions/checkout@v4 + with: + ref: ${{ github.event.pull_request.head.sha }} + fetch-depth: ${{ env.PR_FETCH_DEPTH }} + + - name: Run build-and-test-differential action + uses: ./.github/actions/build-and-test-differential + with: + rosdistro: humble + container: ghcr.io/autowarefoundation/autoware:universe-devel + container-suffix: "" + runner: ubuntu-latest + build-depends-repos: build_depends.repos + build-pre-command: "" + codecov-token: ${{ secrets.CODECOV_TOKEN }} + + build-and-test-differential-cuda: + runs-on: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large + container: ghcr.io/autowarefoundation/autoware:universe-devel-cuda + needs: prepare-build-and-test-differential + if: ${{ needs.prepare-build-and-test-differential.outputs.cuda_build == 'true' }} steps: - name: Set PR fetch depth run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" @@ -62,19 +91,63 @@ jobs: fetch-depth: ${{ env.PR_FETCH_DEPTH }} - name: Run build-and-test-differential action - if: ${{ !(matrix.container-suffix == '-cuda') || needs.make-sure-require-cuda-label-is-present.outputs.result == 'true' }} uses: ./.github/actions/build-and-test-differential with: - rosdistro: ${{ matrix.rosdistro }} - container: ${{ matrix.container }} - container-suffix: ${{ matrix.container-suffix }} - runner: ${{ matrix.runner }} - build-depends-repos: ${{ matrix.build-depends-repos }} - build-pre-command: ${{ matrix.build-pre-command }} + rosdistro: humble + container: ghcr.io/autowarefoundation/autoware:universe-devel + container-suffix: -cuda + runner: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large + build-depends-repos: build_depends.repos + build-pre-command: taskset --cpu-list 0-5 codecov-token: ${{ secrets.CODECOV_TOKEN }} clang-tidy-differential: - needs: build-and-test-differential + needs: [build-and-test-differential, prepare-build-and-test-differential] + if: ${{ needs.prepare-build-and-test-differential.outputs.cuda_build == 'false' }} + runs-on: ubuntu-latest + container: ghcr.io/autowarefoundation/autoware:universe-devel + steps: + - name: Set PR fetch depth + run: echo "PR_FETCH_DEPTH=$(( ${{ github.event.pull_request.commits }} + 1 ))" >> "${GITHUB_ENV}" + + - name: Checkout PR branch and all PR commits + uses: actions/checkout@v4 + with: + ref: ${{ github.event.pull_request.head.sha }} + fetch-depth: ${{ env.PR_FETCH_DEPTH }} + + - name: Show disk space before the tasks + run: df -h + + - name: Remove exec_depend + uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 + + - name: Get modified packages + id: get-modified-packages + uses: autowarefoundation/autoware-github-actions/get-modified-packages@v1 + + - name: Get changed files (existing files only) + id: get-changed-files + run: | + echo "changed-files=$(git diff --name-only "origin/${{ github.base_ref }}"...HEAD | grep -E '\.(cpp|hpp)$' | while read -r file; do [ -e "$file" ] && echo -n "$file "; done)" >> $GITHUB_OUTPUT + shell: bash + + - name: Run clang-tidy + if: ${{ steps.get-changed-files.outputs.changed-files != '' }} + uses: autowarefoundation/autoware-github-actions/clang-tidy@v1 + with: + rosdistro: humble + target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy-ci + clang-tidy-ignore-path: .clang-tidy-ignore + build-depends-repos: build_depends.repos + cache-key-element: cuda + + - name: Show disk space after the tasks + run: df -h + + clang-tidy-differential-cuda: + needs: build-and-test-differential-cuda runs-on: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large container: ghcr.io/autowarefoundation/autoware:universe-devel-cuda steps: From 3dec63b7011f01b97c66a3877786d37c3dc5f375 Mon Sep 17 00:00:00 2001 From: Jesus Armando Anaya Date: Wed, 4 Dec 2024 02:47:34 -0800 Subject: [PATCH 216/273] fix(autoware_carla_interface): include "modules" submodule in release package and update setup.py (#9561) Signed-off-by: Jesus Armando Anaya --- simulator/autoware_carla_interface/setup.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/simulator/autoware_carla_interface/setup.py b/simulator/autoware_carla_interface/setup.py index 346f1838670ab..84f7a544555a2 100644 --- a/simulator/autoware_carla_interface/setup.py +++ b/simulator/autoware_carla_interface/setup.py @@ -1,6 +1,7 @@ from glob import glob import os +from setuptools import find_packages from setuptools import setup package_name = "autoware_carla_interface" @@ -8,13 +9,13 @@ setup( name=package_name, version="0.38.0", - packages=[package_name], + packages=find_packages(where="src"), data_files=[ - ("share/" + package_name, glob("config/*")), - ("share/" + package_name, glob("calibration_maps/*.csv")), - ("share/" + package_name, ["package.xml"]), - (os.path.join("share", package_name), glob("launch/autoware_carla_interface.launch.xml")), - ("share/ament_index/resource_index/packages", ["resource/autoware_carla_interface"]), + ("share/ament_index/resource_index/packages", [f"resource/{package_name}"]), + (os.path.join("share", package_name), ["package.xml"]), + (os.path.join("share", package_name), glob("config/*")), + (os.path.join("share", package_name), glob("calibration_maps/*.csv")), + (os.path.join("share", package_name), glob("launch/*.launch.xml")), ], install_requires=["setuptools"], zip_safe=True, From ed133ebb913390dbd059df294b35fe5b607eca73 Mon Sep 17 00:00:00 2001 From: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Date: Wed, 4 Dec 2024 19:48:47 +0900 Subject: [PATCH 217/273] fix(obstacle_stop_planner): remove stop reason (#9465) Signed-off-by: satoshi-ota --- .../autoware_obstacle_stop_planner/README.md | 7 ++--- .../launch/obstacle_stop_planner.launch.xml | 1 - .../src/debug_marker.cpp | 30 ------------------- .../src/debug_marker.hpp | 6 ---- 4 files changed, 3 insertions(+), 41 deletions(-) diff --git a/planning/autoware_obstacle_stop_planner/README.md b/planning/autoware_obstacle_stop_planner/README.md index d3965192cd4c3..700cb657786ff 100644 --- a/planning/autoware_obstacle_stop_planner/README.md +++ b/planning/autoware_obstacle_stop_planner/README.md @@ -24,10 +24,9 @@ ### Output topics -| Name | Type | Description | -| ---------------------- | ------------------------------------ | -------------------------------------- | -| `~output/trajectory` | autoware_planning_msgs::Trajectory | trajectory to be followed | -| `~output/stop_reasons` | tier4_planning_msgs::StopReasonArray | reasons that cause the vehicle to stop | +| Name | Type | Description | +| -------------------- | ---------------------------------- | ------------------------- | +| `~output/trajectory` | autoware_planning_msgs::Trajectory | trajectory to be followed | ### Common Parameter diff --git a/planning/autoware_obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml b/planning/autoware_obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml index db38370d36dfb..0b0fdc6e00459 100644 --- a/planning/autoware_obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml +++ b/planning/autoware_obstacle_stop_planner/launch/obstacle_stop_planner.launch.xml @@ -22,7 +22,6 @@ - diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp index 75d25f3f8db80..71077014a2be1 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp @@ -47,7 +47,6 @@ ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode( { virtual_wall_pub_ = node_->create_publisher("~/virtual_wall", 1); debug_viz_pub_ = node_->create_publisher("~/debug/marker", 1); - stop_reason_pub_ = node_->create_publisher("~/output/stop_reasons", 1); velocity_factor_pub_ = node_->create_publisher("/planning/velocity_factors/obstacle_stop", 1); pub_debug_values_ = @@ -188,8 +187,6 @@ void ObstacleStopPlannerDebugNode::publish() debug_viz_pub_->publish(visualization_msg); /* publish stop reason for autoware api */ - const auto stop_reason_msg = makeStopReasonArray(); - stop_reason_pub_->publish(stop_reason_msg); const auto velocity_factor_msg = makeVelocityFactorArray(); velocity_factor_pub_->publish(velocity_factor_msg); @@ -493,33 +490,6 @@ MarkerArray ObstacleStopPlannerDebugNode::makeVisualizationMarker() return msg; } -StopReasonArray ObstacleStopPlannerDebugNode::makeStopReasonArray() -{ - // create header - Header header; - header.frame_id = "map"; - header.stamp = node_->now(); - - // create stop reason stamped - StopReason stop_reason_msg; - stop_reason_msg.reason = StopReason::OBSTACLE_STOP; - StopFactor stop_factor; - - if (stop_pose_ptr_ != nullptr) { - stop_factor.stop_pose = *stop_pose_ptr_; - if (stop_obstacle_point_ptr_ != nullptr) { - stop_factor.stop_factor_points.emplace_back(*stop_obstacle_point_ptr_); - } - stop_reason_msg.stop_factors.emplace_back(stop_factor); - } - - // create stop reason array - StopReasonArray stop_reason_array; - stop_reason_array.header = header; - stop_reason_array.stop_reasons.emplace_back(stop_reason_msg); - return stop_reason_array; -} - VelocityFactorArray ObstacleStopPlannerDebugNode::makeVelocityFactorArray() { VelocityFactorArray velocity_factor_array; diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp index 4400368cc3d70..d13e775e3d683 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.hpp @@ -21,7 +21,6 @@ #include #include #include -#include #include #include @@ -47,9 +46,6 @@ using autoware_adapi_v1_msgs::msg::PlanningBehavior; using autoware_adapi_v1_msgs::msg::VelocityFactor; using autoware_adapi_v1_msgs::msg::VelocityFactorArray; using tier4_debug_msgs::msg::Float32MultiArrayStamped; -using tier4_planning_msgs::msg::StopFactor; -using tier4_planning_msgs::msg::StopReason; -using tier4_planning_msgs::msg::StopReasonArray; enum class PolygonType : int8_t { Vehicle = 0, Collision, SlowDownRange, SlowDown, Obstacle }; @@ -113,7 +109,6 @@ class ObstacleStopPlannerDebugNode bool pushObstaclePoint(const pcl::PointXYZ & obstacle_point, const PointType & type); MarkerArray makeVirtualWallMarker(); MarkerArray makeVisualizationMarker(); - StopReasonArray makeStopReasonArray(); VelocityFactorArray makeVelocityFactorArray(); void setDebugValues(const DebugValues::TYPE type, const double val) @@ -125,7 +120,6 @@ class ObstacleStopPlannerDebugNode private: rclcpp::Publisher::SharedPtr virtual_wall_pub_; rclcpp::Publisher::SharedPtr debug_viz_pub_; - rclcpp::Publisher::SharedPtr stop_reason_pub_; rclcpp::Publisher::SharedPtr velocity_factor_pub_; rclcpp::Publisher::SharedPtr pub_debug_values_; rclcpp::Node * node_; From 6ab469d73e6a195095c5e0312bc51d85981b6c7b Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 4 Dec 2024 14:06:12 +0100 Subject: [PATCH 218/273] refactor(glog_component): prefix package and namespace with autoware (#9302) Signed-off-by: Esteve Fernandez Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> --- .github/CODEOWNERS | 2 +- common/.pages | 2 +- .../CHANGELOG.rst | 0 common/autoware_glog_component/CMakeLists.txt | 18 ++++++++++++++++++ .../README.md | 4 ++-- .../glog_component/glog_component.hpp | 11 ++++++++--- .../package.xml | 4 ++-- .../src/glog_component.cpp | 9 +++++++-- common/glog_component/CMakeLists.txt | 18 ------------------ .../launch/control.launch.xml | 4 ++-- .../behavior_planning.launch.xml | 2 +- .../motion_planning/motion_planning.launch.xml | 2 +- .../scenario_planning/parking.launch.xml | 2 +- .../scenario_planning.launch.xml | 2 +- launch/tier4_planning_launch/package.xml | 2 +- .../launch/mission_planner.launch.xml | 2 +- 16 files changed, 47 insertions(+), 37 deletions(-) rename common/{glog_component => autoware_glog_component}/CHANGELOG.rst (100%) create mode 100644 common/autoware_glog_component/CMakeLists.txt rename common/{glog_component => autoware_glog_component}/README.md (88%) rename common/{glog_component/include => autoware_glog_component/include/autoware}/glog_component/glog_component.hpp (75%) rename common/{glog_component => autoware_glog_component}/package.xml (87%) rename common/{glog_component => autoware_glog_component}/src/glog_component.cpp (81%) delete mode 100644 common/glog_component/CMakeLists.txt diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index b2d0098cfecec..b2a48d9229ed7 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -6,6 +6,7 @@ common/autoware_component_interface_tools/** isamu.takagi@tier4.jp common/autoware_component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/autoware_fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_geography_utils/** anh.nguyen.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +common/autoware_glog_component/** takamasa.horibe@tier4.jp common/autoware_goal_distance_calculator/** taiki.tanaka@tier4.jp common/autoware_grid_map_utils/** maxime.clement@tier4.jp common/autoware_interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp @@ -31,7 +32,6 @@ common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp -common/glog_component/** takamasa.horibe@tier4.jp common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp common/tier4_api_utils/** isamu.takagi@tier4.jp common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp diff --git a/common/.pages b/common/.pages index 27ee85c30ea77..26117d6becada 100644 --- a/common/.pages +++ b/common/.pages @@ -11,7 +11,7 @@ nav: - 'autoware_point_types': common/autoware_point_types - 'Geography Utils': common/autoware_geography_utils - 'Global Parameter Loader': common/global_parameter_loader/Readme - - 'Glog Component': common/glog_component + - 'Glog Component': common/autoware_glog_component - 'interpolation': common/autoware_interpolation - 'Kalman Filter': common/autoware_kalman_filter - 'Motion Utils': common/autoware_motion_utils diff --git a/common/glog_component/CHANGELOG.rst b/common/autoware_glog_component/CHANGELOG.rst similarity index 100% rename from common/glog_component/CHANGELOG.rst rename to common/autoware_glog_component/CHANGELOG.rst diff --git a/common/autoware_glog_component/CMakeLists.txt b/common/autoware_glog_component/CMakeLists.txt new file mode 100644 index 0000000000000..37e2862517bc1 --- /dev/null +++ b/common/autoware_glog_component/CMakeLists.txt @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_glog_component) + +find_package(autoware_cmake REQUIRED) +autoware_package() + + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/glog_component.cpp +) +target_link_libraries(${PROJECT_NAME} glog::glog) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::glog_component::GlogComponent" + EXECUTABLE ${PROJECT_NAME}_node +) + +ament_auto_package() diff --git a/common/glog_component/README.md b/common/autoware_glog_component/README.md similarity index 88% rename from common/glog_component/README.md rename to common/autoware_glog_component/README.md index 94a40fe32e40d..ae8d8e5b9b8f2 100644 --- a/common/glog_component/README.md +++ b/common/autoware_glog_component/README.md @@ -10,8 +10,8 @@ When you load the `glog_component` in container, the launch file can be like bel ```py glog_component = ComposableNode( - package="glog_component", - plugin="GlogComponent", + package="autoware_glog_component", + plugin="autoware::glog_component::GlogComponent", name="glog_component", ) diff --git a/common/glog_component/include/glog_component/glog_component.hpp b/common/autoware_glog_component/include/autoware/glog_component/glog_component.hpp similarity index 75% rename from common/glog_component/include/glog_component/glog_component.hpp rename to common/autoware_glog_component/include/autoware/glog_component/glog_component.hpp index d940363d75ac4..8e0a45d4e32c8 100644 --- a/common/glog_component/include/glog_component/glog_component.hpp +++ b/common/autoware_glog_component/include/autoware/glog_component/glog_component.hpp @@ -12,17 +12,22 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef GLOG_COMPONENT__GLOG_COMPONENT_HPP_ -#define GLOG_COMPONENT__GLOG_COMPONENT_HPP_ +#ifndef AUTOWARE__GLOG_COMPONENT__GLOG_COMPONENT_HPP_ +#define AUTOWARE__GLOG_COMPONENT__GLOG_COMPONENT_HPP_ #include #include +namespace autoware::glog_component +{ + class GlogComponent : public rclcpp::Node { public: explicit GlogComponent(const rclcpp::NodeOptions & node_options); }; -#endif // GLOG_COMPONENT__GLOG_COMPONENT_HPP_ +} // namespace autoware::glog_component + +#endif // AUTOWARE__GLOG_COMPONENT__GLOG_COMPONENT_HPP_ diff --git a/common/glog_component/package.xml b/common/autoware_glog_component/package.xml similarity index 87% rename from common/glog_component/package.xml rename to common/autoware_glog_component/package.xml index a9e7cdf54fd5a..f9e6a1aa26723 100644 --- a/common/glog_component/package.xml +++ b/common/autoware_glog_component/package.xml @@ -1,9 +1,9 @@ - glog_component + autoware_glog_component 0.38.0 - The glog_component package + The autoware_glog_component package Takamasa Horibe Apache License 2.0 diff --git a/common/glog_component/src/glog_component.cpp b/common/autoware_glog_component/src/glog_component.cpp similarity index 81% rename from common/glog_component/src/glog_component.cpp rename to common/autoware_glog_component/src/glog_component.cpp index 7fd9c923d23c9..cddfd206668be 100644 --- a/common/glog_component/src/glog_component.cpp +++ b/common/autoware_glog_component/src/glog_component.cpp @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "glog_component/glog_component.hpp" +#include "autoware/glog_component/glog_component.hpp" + +namespace autoware::glog_component +{ GlogComponent::GlogComponent(const rclcpp::NodeOptions & node_options) : Node("glog_component", node_options) @@ -23,5 +26,7 @@ GlogComponent::GlogComponent(const rclcpp::NodeOptions & node_options) } } +} // namespace autoware::glog_component + #include -RCLCPP_COMPONENTS_REGISTER_NODE(GlogComponent) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::glog_component::GlogComponent) diff --git a/common/glog_component/CMakeLists.txt b/common/glog_component/CMakeLists.txt deleted file mode 100644 index a233914cc1524..0000000000000 --- a/common/glog_component/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(glog_component) - -find_package(autoware_cmake REQUIRED) -autoware_package() - - -ament_auto_add_library(glog_component SHARED - src/glog_component.cpp -) -target_link_libraries(glog_component glog::glog) - -rclcpp_components_register_node(glog_component - PLUGIN "GlogComponent" - EXECUTABLE glog_component_node -) - -ament_auto_package() diff --git a/launch/tier4_control_launch/launch/control.launch.xml b/launch/tier4_control_launch/launch/control.launch.xml index 387b82526f624..a979f9e28244b 100644 --- a/launch/tier4_control_launch/launch/control.launch.xml +++ b/launch/tier4_control_launch/launch/control.launch.xml @@ -51,7 +51,7 @@ - + @@ -177,7 +177,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index dad351dec40e8..41326c1a16728 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -255,7 +255,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index b303134ab80c3..fb7e11419fdc9 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -27,7 +27,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml index e0fdcb1e30408..89961821fa761 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml @@ -32,7 +32,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml index 9082ebab013ed..a89b47da13049 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -44,7 +44,7 @@ - + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index f0fe45a46d92a..7f181d6d707b6 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -63,6 +63,7 @@ autoware_external_cmd_selector autoware_external_velocity_limit_selector autoware_freespace_planner + autoware_glog_component autoware_mission_planner autoware_obstacle_cruise_planner autoware_obstacle_stop_planner @@ -74,7 +75,6 @@ autoware_scenario_selector autoware_surround_obstacle_checker autoware_velocity_smoother - glog_component ament_lint_auto autoware_lint_common diff --git a/planning/autoware_mission_planner/launch/mission_planner.launch.xml b/planning/autoware_mission_planner/launch/mission_planner.launch.xml index 8d77e417a6379..0d9c9307d549c 100644 --- a/planning/autoware_mission_planner/launch/mission_planner.launch.xml +++ b/planning/autoware_mission_planner/launch/mission_planner.launch.xml @@ -23,6 +23,6 @@ - + From 53691e401f265bb9b1b316258ba8932adb9b5aae Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Wed, 4 Dec 2024 15:24:21 +0100 Subject: [PATCH 219/273] refactor(global_parameter_loader): prefix package and namespace with autoware (#9303) Signed-off-by: Esteve Fernandez --- .github/CODEOWNERS | 2 +- common/.pages | 2 +- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 2 +- .../Readme.md | 2 +- .../launch/global_params.launch.py | 0 .../package.xml | 4 ++-- control/control_performance_analysis/package.xml | 2 +- .../launch/launch_visualization.launch.xml | 2 +- .../launch/static_centerline_generator.launch.xml | 2 +- planning/autoware_static_centerline_generator/package.xml | 2 +- .../launch/steer_offset_estimator.launch.xml | 2 +- vehicle/autoware_steer_offset_estimator/package.xml | 2 +- 13 files changed, 12 insertions(+), 12 deletions(-) rename common/{global_parameter_loader => autoware_global_parameter_loader}/CHANGELOG.rst (100%) rename common/{global_parameter_loader => autoware_global_parameter_loader}/CMakeLists.txt (77%) rename common/{global_parameter_loader => autoware_global_parameter_loader}/Readme.md (83%) rename common/{global_parameter_loader => autoware_global_parameter_loader}/launch/global_params.launch.py (100%) rename common/{global_parameter_loader => autoware_global_parameter_loader}/package.xml (84%) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index b2a48d9229ed7..4923e144f2886 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -6,6 +6,7 @@ common/autoware_component_interface_tools/** isamu.takagi@tier4.jp common/autoware_component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/autoware_fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp common/autoware_geography_utils/** anh.nguyen.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp +common/autoware_global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/autoware_glog_component/** takamasa.horibe@tier4.jp common/autoware_goal_distance_calculator/** taiki.tanaka@tier4.jp common/autoware_grid_map_utils/** maxime.clement@tier4.jp @@ -31,7 +32,6 @@ common/autoware_trajectory/** mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yu common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp -common/global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp common/tier4_api_utils/** isamu.takagi@tier4.jp common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp diff --git a/common/.pages b/common/.pages index 26117d6becada..3c5a77c4d68cf 100644 --- a/common/.pages +++ b/common/.pages @@ -10,7 +10,7 @@ nav: - 'autoware_grid_map_utils': common/autoware_grid_map_utils - 'autoware_point_types': common/autoware_point_types - 'Geography Utils': common/autoware_geography_utils - - 'Global Parameter Loader': common/global_parameter_loader/Readme + - 'Global Parameter Loader': common/autoware_global_parameter_loader/Readme - 'Glog Component': common/autoware_glog_component - 'interpolation': common/autoware_interpolation - 'Kalman Filter': common/autoware_kalman_filter diff --git a/common/global_parameter_loader/CHANGELOG.rst b/common/autoware_global_parameter_loader/CHANGELOG.rst similarity index 100% rename from common/global_parameter_loader/CHANGELOG.rst rename to common/autoware_global_parameter_loader/CHANGELOG.rst diff --git a/common/global_parameter_loader/CMakeLists.txt b/common/autoware_global_parameter_loader/CMakeLists.txt similarity index 77% rename from common/global_parameter_loader/CMakeLists.txt rename to common/autoware_global_parameter_loader/CMakeLists.txt index e67ae1a5c06fc..fe47ffc0c845b 100644 --- a/common/global_parameter_loader/CMakeLists.txt +++ b/common/autoware_global_parameter_loader/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(global_parameter_loader) +project(autoware_global_parameter_loader) find_package(autoware_cmake REQUIRED) autoware_package() diff --git a/common/global_parameter_loader/Readme.md b/common/autoware_global_parameter_loader/Readme.md similarity index 83% rename from common/global_parameter_loader/Readme.md rename to common/autoware_global_parameter_loader/Readme.md index 53cb9e11e096f..7b818c26a87f2 100644 --- a/common/global_parameter_loader/Readme.md +++ b/common/autoware_global_parameter_loader/Readme.md @@ -8,7 +8,7 @@ Add the following lines to the launch file of the node in which you want to get ```xml - + ``` diff --git a/common/global_parameter_loader/launch/global_params.launch.py b/common/autoware_global_parameter_loader/launch/global_params.launch.py similarity index 100% rename from common/global_parameter_loader/launch/global_params.launch.py rename to common/autoware_global_parameter_loader/launch/global_params.launch.py diff --git a/common/global_parameter_loader/package.xml b/common/autoware_global_parameter_loader/package.xml similarity index 84% rename from common/global_parameter_loader/package.xml rename to common/autoware_global_parameter_loader/package.xml index 64183edaa6b1a..2a72f93230da9 100644 --- a/common/global_parameter_loader/package.xml +++ b/common/autoware_global_parameter_loader/package.xml @@ -1,9 +1,9 @@ - global_parameter_loader + autoware_global_parameter_loader 0.38.0 - The global_parameter_loader package + The autoware_global_parameter_loader package Ryohsuke Mitsudome Apache License 2.0 diff --git a/control/control_performance_analysis/package.xml b/control/control_performance_analysis/package.xml index 4f149a3846595..203357d3f0474 100644 --- a/control/control_performance_analysis/package.xml +++ b/control/control_performance_analysis/package.xml @@ -42,8 +42,8 @@ tf2_eigen tf2_ros tier4_debug_msgs + autoware_global_parameter_loader builtin_interfaces - global_parameter_loader rosidl_default_runtime ament_lint_auto autoware_lint_common diff --git a/planning/autoware_path_optimizer/launch/launch_visualization.launch.xml b/planning/autoware_path_optimizer/launch/launch_visualization.launch.xml index 38b3d83e94991..1a65357e52d53 100644 --- a/planning/autoware_path_optimizer/launch/launch_visualization.launch.xml +++ b/planning/autoware_path_optimizer/launch/launch_visualization.launch.xml @@ -5,7 +5,7 @@ - + diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml index 7d97caf4b375f..9ccc5a183be45 100644 --- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -35,7 +35,7 @@ - + diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index 5375f50c642b7..b9b1267a343db 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -17,6 +17,7 @@ autoware_behavior_path_planner_common autoware_geography_utils + autoware_global_parameter_loader autoware_interpolation autoware_lanelet2_extension autoware_map_loader @@ -33,7 +34,6 @@ autoware_universe_utils autoware_vehicle_info_utils geometry_msgs - global_parameter_loader rclcpp rclcpp_components diff --git a/vehicle/autoware_steer_offset_estimator/launch/steer_offset_estimator.launch.xml b/vehicle/autoware_steer_offset_estimator/launch/steer_offset_estimator.launch.xml index 919858950e69c..ef298696692bd 100644 --- a/vehicle/autoware_steer_offset_estimator/launch/steer_offset_estimator.launch.xml +++ b/vehicle/autoware_steer_offset_estimator/launch/steer_offset_estimator.launch.xml @@ -3,7 +3,7 @@ - + diff --git a/vehicle/autoware_steer_offset_estimator/package.xml b/vehicle/autoware_steer_offset_estimator/package.xml index 561cb85e0d806..27096dd20ab28 100644 --- a/vehicle/autoware_steer_offset_estimator/package.xml +++ b/vehicle/autoware_steer_offset_estimator/package.xml @@ -18,8 +18,8 @@ rclcpp_components std_msgs tier4_debug_msgs + autoware_global_parameter_loader autoware_pose2twist - global_parameter_loader ament_lint_auto autoware_lint_common From 00777dcc50f7f44b052bbc6a5c2eb15bf3988de9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:12:56 +0300 Subject: [PATCH 220/273] fix(cpplint): include what you use - common (#9564) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../test/test_component_interface_utils.cpp | 4 ++++ common/autoware_geography_utils/src/lanelet2_projector.cpp | 3 +++ common/autoware_geography_utils/src/projection.cpp | 2 ++ common/autoware_grid_map_utils/src/polygon_iterator.cpp | 1 + .../src/spherical_linear_interpolation.cpp | 2 ++ .../autoware_kalman_filter/src/time_delay_kalman_filter.cpp | 2 ++ common/autoware_motion_utils/src/distance/distance.cpp | 2 ++ .../src/factor/steering_factor_interface.cpp | 2 ++ .../src/factor/velocity_factor_interface.cpp | 3 +++ common/autoware_motion_utils/src/marker/marker_helper.cpp | 2 ++ common/autoware_motion_utils/src/resample/resample.cpp | 3 +++ common/autoware_motion_utils/src/trajectory/conversion.cpp | 1 + common/autoware_motion_utils/src/trajectory/path_shift.cpp | 3 +++ common/autoware_motion_utils/src/trajectory/trajectory.cpp | 4 ++++ .../test/src/marker/test_virtual_wall_marker_creator.cpp | 3 +++ .../test/src/resample/test_resample.cpp | 1 + .../test/src/trajectory/test_trajectory.cpp | 1 + .../src/predicted_path_utils.cpp | 1 + .../test/src/test_object_classification.cpp | 2 ++ .../test/src/test_predicted_path_utils.cpp | 2 ++ common/autoware_osqp_interface/test/test_osqp_interface.cpp | 1 + .../src/overlay_utils.cpp | 2 ++ .../src/remaining_distance_time_display.cpp | 1 + .../autoware_overlay_rviz_plugin/src/gear_display.cpp | 1 + .../autoware_overlay_rviz_plugin/src/overlay_utils.cpp | 2 ++ .../autoware_overlay_rviz_plugin/src/speed_display.cpp | 1 + .../autoware_overlay_rviz_plugin/src/speed_limit_display.cpp | 1 + .../src/steering_wheel_display.cpp | 1 + .../src/turn_signals_display.cpp | 1 + .../src/object_detection/predicted_objects_display.cpp | 1 + common/autoware_qp_interface/src/osqp_interface.cpp | 5 +++++ common/autoware_qp_interface/src/proxqp_interface.cpp | 4 ++++ common/autoware_qp_interface/test/test_osqp_interface.cpp | 2 ++ common/autoware_qp_interface/test/test_proxqp_interface.cpp | 2 ++ common/autoware_signal_processing/src/butterworth.cpp | 1 + .../test/src/butterworth_filter_test.cpp | 2 ++ common/autoware_test_utils/src/autoware_test_utils.cpp | 2 ++ common/autoware_test_utils/src/topic_snapshot_saver.cpp | 5 +++++ .../autoware_test_utils/test/test_autoware_test_manager.cpp | 3 +++ common/autoware_test_utils/test/test_mock_data_parser.cpp | 2 ++ .../src/traffic_light_recognition_marker_publisher.cpp | 1 + .../autoware_traffic_light_utils/src/traffic_light_utils.cpp | 2 ++ .../examples/example_trajectory_path_point.cpp | 1 + common/autoware_trajectory/src/path_point.cpp | 2 ++ common/autoware_trajectory/src/point.cpp | 1 + .../autoware_trajectory/test/test_trajectory_container.cpp | 1 + .../autoware_universe_utils/examples/example_lru_cache.cpp | 2 ++ .../examples/example_polling_subscriber.cpp | 2 ++ common/autoware_universe_utils/src/geometry/alt_geometry.cpp | 5 +++++ common/autoware_universe_utils/src/geometry/ear_clipping.cpp | 4 ++++ common/autoware_universe_utils/src/geometry/geometry.cpp | 2 ++ .../src/geometry/random_concave_polygon.cpp | 5 +++++ common/autoware_universe_utils/src/geometry/sat_2d.cpp | 2 ++ common/autoware_universe_utils/src/math/trigonometry.cpp | 1 + common/autoware_universe_utils/src/ros/marker_helper.cpp | 2 ++ common/autoware_universe_utils/src/system/time_keeper.cpp | 2 ++ .../test/src/geometry/test_alt_geometry.cpp | 3 +++ .../test/src/geometry/test_geometry.cpp | 3 +++ .../test/src/ros/test_managed_transform_buffer.cpp | 1 + .../test/src/ros/test_published_time_publisher.cpp | 4 ++++ .../test/src/system/test_time_keeper.cpp | 2 ++ common/autoware_vehicle_info_utils/src/vehicle_info.cpp | 2 ++ .../test/test_vehicle_info_utils.cpp | 2 ++ .../src/bag_time_manager_panel.cpp | 2 ++ .../src/pose_history/pose_history_display.cpp | 2 ++ .../src/pose_history_footprint/display.cpp | 2 ++ .../pose_with_covariance_history_display.cpp | 2 ++ common/tier4_planning_rviz_plugin/src/path/display.cpp | 4 ++++ .../src/pose_with_uuid_stamped/display.cpp | 3 +++ .../src/velocity_steering_factors_panel.cpp | 1 + 70 files changed, 152 insertions(+) diff --git a/common/autoware_component_interface_utils/test/test_component_interface_utils.cpp b/common/autoware_component_interface_utils/test/test_component_interface_utils.cpp index 7cf2dccf3e764..6919271214983 100644 --- a/common/autoware_component_interface_utils/test/test_component_interface_utils.cpp +++ b/common/autoware_component_interface_utils/test/test_component_interface_utils.cpp @@ -17,6 +17,10 @@ #include "autoware/component_interface_utils/status.hpp" #include "gtest/gtest.h" +#include +#include +#include + TEST(interface, utils) { { diff --git a/common/autoware_geography_utils/src/lanelet2_projector.cpp b/common/autoware_geography_utils/src/lanelet2_projector.cpp index 7de0935a3aa4e..76c69a85ae0bc 100644 --- a/common/autoware_geography_utils/src/lanelet2_projector.cpp +++ b/common/autoware_geography_utils/src/lanelet2_projector.cpp @@ -19,6 +19,9 @@ #include +#include +#include + namespace autoware::geography_utils { diff --git a/common/autoware_geography_utils/src/projection.cpp b/common/autoware_geography_utils/src/projection.cpp index 3ab18b1d31698..e113c8da7b519 100644 --- a/common/autoware_geography_utils/src/projection.cpp +++ b/common/autoware_geography_utils/src/projection.cpp @@ -17,6 +17,8 @@ #include #include +#include + namespace autoware::geography_utils { diff --git a/common/autoware_grid_map_utils/src/polygon_iterator.cpp b/common/autoware_grid_map_utils/src/polygon_iterator.cpp index d3c5de85c2ed2..47ff9a9e5957f 100644 --- a/common/autoware_grid_map_utils/src/polygon_iterator.cpp +++ b/common/autoware_grid_map_utils/src/polygon_iterator.cpp @@ -21,6 +21,7 @@ #include #include #include +#include namespace autoware::grid_map_utils { diff --git a/common/autoware_interpolation/src/spherical_linear_interpolation.cpp b/common/autoware_interpolation/src/spherical_linear_interpolation.cpp index 697dda3b06770..5acdf6a9036a3 100644 --- a/common/autoware_interpolation/src/spherical_linear_interpolation.cpp +++ b/common/autoware_interpolation/src/spherical_linear_interpolation.cpp @@ -14,6 +14,8 @@ #include "autoware/interpolation/spherical_linear_interpolation.hpp" +#include + namespace autoware::interpolation { geometry_msgs::msg::Quaternion slerp( diff --git a/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp b/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp index 31c1c768d7173..4d1dd8f33b7a6 100644 --- a/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp +++ b/common/autoware_kalman_filter/src/time_delay_kalman_filter.cpp @@ -14,6 +14,8 @@ #include "autoware/kalman_filter/time_delay_kalman_filter.hpp" +#include + namespace autoware::kalman_filter { TimeDelayKalmanFilter::TimeDelayKalmanFilter() diff --git a/common/autoware_motion_utils/src/distance/distance.cpp b/common/autoware_motion_utils/src/distance/distance.cpp index d31e7ec709810..c218561beacec 100644 --- a/common/autoware_motion_utils/src/distance/distance.cpp +++ b/common/autoware_motion_utils/src/distance/distance.cpp @@ -14,6 +14,8 @@ #include "autoware/motion_utils/distance/distance.hpp" +#include + namespace autoware::motion_utils { namespace diff --git a/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp b/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp index f85b5b26cd0c2..7f12e2972ec86 100644 --- a/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp +++ b/common/autoware_motion_utils/src/factor/steering_factor_interface.cpp @@ -14,6 +14,8 @@ #include +#include + namespace autoware::motion_utils { void SteeringFactorInterface::set( diff --git a/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp b/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp index 6a1ddff453bd0..cfa3c91eac43e 100644 --- a/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp +++ b/common/autoware_motion_utils/src/factor/velocity_factor_interface.cpp @@ -19,6 +19,9 @@ #include #include +#include +#include + namespace autoware::motion_utils { template diff --git a/common/autoware_motion_utils/src/marker/marker_helper.cpp b/common/autoware_motion_utils/src/marker/marker_helper.cpp index 29462afcb5b76..91ad1c41eecc3 100644 --- a/common/autoware_motion_utils/src/marker/marker_helper.cpp +++ b/common/autoware_motion_utils/src/marker/marker_helper.cpp @@ -20,6 +20,8 @@ #include +#include + using autoware::universe_utils::createDefaultMarker; using autoware::universe_utils::createDeletedDefaultMarker; using autoware::universe_utils::createMarkerColor; diff --git a/common/autoware_motion_utils/src/resample/resample.cpp b/common/autoware_motion_utils/src/resample/resample.cpp index 88ebf3f41c408..9e736444495fa 100644 --- a/common/autoware_motion_utils/src/resample/resample.cpp +++ b/common/autoware_motion_utils/src/resample/resample.cpp @@ -21,7 +21,10 @@ #include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" +#include #include +#include +#include namespace autoware::motion_utils { diff --git a/common/autoware_motion_utils/src/trajectory/conversion.cpp b/common/autoware_motion_utils/src/trajectory/conversion.cpp index 368d3e0fbbb75..706dd6dae79af 100644 --- a/common/autoware_motion_utils/src/trajectory/conversion.cpp +++ b/common/autoware_motion_utils/src/trajectory/conversion.cpp @@ -15,6 +15,7 @@ #include "autoware/motion_utils/trajectory/conversion.hpp" #include +#include namespace autoware::motion_utils { diff --git a/common/autoware_motion_utils/src/trajectory/path_shift.cpp b/common/autoware_motion_utils/src/trajectory/path_shift.cpp index 6f57f34a56190..8864128f94bd9 100644 --- a/common/autoware_motion_utils/src/trajectory/path_shift.cpp +++ b/common/autoware_motion_utils/src/trajectory/path_shift.cpp @@ -16,6 +16,9 @@ #include "autoware/motion_utils/trajectory/trajectory.hpp" +#include +#include + namespace autoware::motion_utils { double calc_feasible_velocity_from_jerk( diff --git a/common/autoware_motion_utils/src/trajectory/trajectory.cpp b/common/autoware_motion_utils/src/trajectory/trajectory.cpp index 080d8ca8c7437..35e39fda75a69 100644 --- a/common/autoware_motion_utils/src/trajectory/trajectory.cpp +++ b/common/autoware_motion_utils/src/trajectory/trajectory.cpp @@ -14,6 +14,10 @@ #include "autoware/motion_utils/trajectory/trajectory.hpp" +#include +#include +#include + namespace autoware::motion_utils { diff --git a/common/autoware_motion_utils/test/src/marker/test_virtual_wall_marker_creator.cpp b/common/autoware_motion_utils/test/src/marker/test_virtual_wall_marker_creator.cpp index 5e2e0cc4bdf02..afce7f953e644 100644 --- a/common/autoware_motion_utils/test/src/marker/test_virtual_wall_marker_creator.cpp +++ b/common/autoware_motion_utils/test/src/marker/test_virtual_wall_marker_creator.cpp @@ -14,6 +14,9 @@ #include "autoware/motion_utils/marker/virtual_wall_marker_creator.hpp" #include "gtest/gtest.h" + +#include + namespace { constexpr auto wall_ns_suffix = "_virtual_wall"; diff --git a/common/autoware_motion_utils/test/src/resample/test_resample.cpp b/common/autoware_motion_utils/test/src/resample/test_resample.cpp index 68ead4b8c1520..ef97dfa410d2d 100644 --- a/common/autoware_motion_utils/test/src/resample/test_resample.cpp +++ b/common/autoware_motion_utils/test/src/resample/test_resample.cpp @@ -24,6 +24,7 @@ #include #include +#include namespace { diff --git a/common/autoware_motion_utils/test/src/trajectory/test_trajectory.cpp b/common/autoware_motion_utils/test/src/trajectory/test_trajectory.cpp index 4ff9b2a33ca13..f34365b08a943 100644 --- a/common/autoware_motion_utils/test/src/trajectory/test_trajectory.cpp +++ b/common/autoware_motion_utils/test/src/trajectory/test_trajectory.cpp @@ -21,6 +21,7 @@ #include #include +#include #include #include diff --git a/common/autoware_object_recognition_utils/src/predicted_path_utils.cpp b/common/autoware_object_recognition_utils/src/predicted_path_utils.cpp index 196f82b69161a..55ac4e2a370c3 100644 --- a/common/autoware_object_recognition_utils/src/predicted_path_utils.cpp +++ b/common/autoware_object_recognition_utils/src/predicted_path_utils.cpp @@ -19,6 +19,7 @@ #include "autoware/interpolation/spline_interpolation.hpp" #include +#include namespace autoware::object_recognition_utils { diff --git a/common/autoware_object_recognition_utils/test/src/test_object_classification.cpp b/common/autoware_object_recognition_utils/test/src/test_object_classification.cpp index 1482158581a8e..31d2a90f2e4a5 100644 --- a/common/autoware_object_recognition_utils/test/src/test_object_classification.cpp +++ b/common/autoware_object_recognition_utils/test/src/test_object_classification.cpp @@ -16,6 +16,8 @@ #include +#include + constexpr double epsilon = 1e-06; namespace diff --git a/common/autoware_object_recognition_utils/test/src/test_predicted_path_utils.cpp b/common/autoware_object_recognition_utils/test/src/test_predicted_path_utils.cpp index a93d253bfd052..1f434d3362b86 100644 --- a/common/autoware_object_recognition_utils/test/src/test_predicted_path_utils.cpp +++ b/common/autoware_object_recognition_utils/test/src/test_predicted_path_utils.cpp @@ -20,6 +20,8 @@ #include +#include + using autoware::universe_utils::Point2d; using autoware::universe_utils::Point3d; diff --git a/common/autoware_osqp_interface/test/test_osqp_interface.cpp b/common/autoware_osqp_interface/test/test_osqp_interface.cpp index d03713f82566f..f65b07e6d792d 100644 --- a/common/autoware_osqp_interface/test/test_osqp_interface.cpp +++ b/common/autoware_osqp_interface/test/test_osqp_interface.cpp @@ -17,6 +17,7 @@ #include +#include #include #include diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp index 68813a5f1140f..7989dd21d8b2e 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp @@ -52,6 +52,8 @@ #include +#include + namespace autoware::mission_details_overlay_rviz_plugin { ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp index 13f3fdddfe76b..41ee64f5233a7 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -23,6 +23,7 @@ #include #include +#include #include #include diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp index 03729d122e614..12e25ee3bb954 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp index d6f061e724369..076b92a415ee0 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp @@ -52,6 +52,8 @@ #include +#include + namespace autoware_overlay_rviz_plugin { ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer) diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp index d677be40dead2..faf9c39af672d 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp index 1da64aaf320ca..36b5212c08f75 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp index 28bd2b5c2a52e..d475a8231e595 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp index b42b5d953fcc6..6748f01fe139b 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include diff --git a/common/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp b/common/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp index d11aba912854d..b95b94248c943 100644 --- a/common/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp +++ b/common/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp @@ -16,6 +16,7 @@ #include #include +#include namespace autoware { diff --git a/common/autoware_qp_interface/src/osqp_interface.cpp b/common/autoware_qp_interface/src/osqp_interface.cpp index b850036c0aebf..fbb8e71f4c251 100644 --- a/common/autoware_qp_interface/src/osqp_interface.cpp +++ b/common/autoware_qp_interface/src/osqp_interface.cpp @@ -18,6 +18,11 @@ #include +#include +#include +#include +#include + namespace autoware::qp_interface { OSQPInterface::OSQPInterface( diff --git a/common/autoware_qp_interface/src/proxqp_interface.cpp b/common/autoware_qp_interface/src/proxqp_interface.cpp index ccfd74e70dace..a0ebbf0db0510 100644 --- a/common/autoware_qp_interface/src/proxqp_interface.cpp +++ b/common/autoware_qp_interface/src/proxqp_interface.cpp @@ -14,6 +14,10 @@ #include "autoware/qp_interface/proxqp_interface.hpp" +#include +#include +#include + namespace autoware::qp_interface { using proxsuite::proxqp::QPSolverOutput; diff --git a/common/autoware_qp_interface/test/test_osqp_interface.cpp b/common/autoware_qp_interface/test/test_osqp_interface.cpp index 873e5d501dc7d..f97cc2888afa0 100644 --- a/common/autoware_qp_interface/test/test_osqp_interface.cpp +++ b/common/autoware_qp_interface/test/test_osqp_interface.cpp @@ -17,6 +17,8 @@ #include +#include +#include #include #include diff --git a/common/autoware_qp_interface/test/test_proxqp_interface.cpp b/common/autoware_qp_interface/test/test_proxqp_interface.cpp index 5bf85b026478d..e47af10c7aabd 100644 --- a/common/autoware_qp_interface/test/test_proxqp_interface.cpp +++ b/common/autoware_qp_interface/test/test_proxqp_interface.cpp @@ -17,6 +17,8 @@ #include +#include +#include #include #include diff --git a/common/autoware_signal_processing/src/butterworth.cpp b/common/autoware_signal_processing/src/butterworth.cpp index 7f491d443787b..0143b7b4fe273 100644 --- a/common/autoware_signal_processing/src/butterworth.cpp +++ b/common/autoware_signal_processing/src/butterworth.cpp @@ -19,6 +19,7 @@ #include #include #include +#include namespace autoware::signal_processing { diff --git a/common/autoware_signal_processing/test/src/butterworth_filter_test.cpp b/common/autoware_signal_processing/test/src/butterworth_filter_test.cpp index bd5d1dbbf6948..8fa72676b02cc 100644 --- a/common/autoware_signal_processing/test/src/butterworth_filter_test.cpp +++ b/common/autoware_signal_processing/test/src/butterworth_filter_test.cpp @@ -14,6 +14,8 @@ #include "butterworth_filter_test.hpp" +#include + using autoware::signal_processing::ButterworthFilter; TEST_F(ButterWorthTestFixture, butterworthOrderTest) diff --git a/common/autoware_test_utils/src/autoware_test_utils.cpp b/common/autoware_test_utils/src/autoware_test_utils.cpp index d61dc61c81e65..d42a5219e374c 100644 --- a/common/autoware_test_utils/src/autoware_test_utils.cpp +++ b/common/autoware_test_utils/src/autoware_test_utils.cpp @@ -26,7 +26,9 @@ #include #include +#include #include +#include namespace autoware::test_utils { diff --git a/common/autoware_test_utils/src/topic_snapshot_saver.cpp b/common/autoware_test_utils/src/topic_snapshot_saver.cpp index 82700be9e3f54..b2cb2a17c9621 100644 --- a/common/autoware_test_utils/src/topic_snapshot_saver.cpp +++ b/common/autoware_test_utils/src/topic_snapshot_saver.cpp @@ -29,10 +29,15 @@ #include #include +#include +#include #include #include +#include #include +#include #include +#include using MessageType = std::variant< nav_msgs::msg::Odometry, // 0 diff --git a/common/autoware_test_utils/test/test_autoware_test_manager.cpp b/common/autoware_test_utils/test/test_autoware_test_manager.cpp index 688ec9df9ad42..9e0e00d199f67 100644 --- a/common/autoware_test_utils/test/test_autoware_test_manager.cpp +++ b/common/autoware_test_utils/test/test_autoware_test_manager.cpp @@ -20,6 +20,9 @@ #include +#include +#include + class RelayNode : public rclcpp::Node { public: diff --git a/common/autoware_test_utils/test/test_mock_data_parser.cpp b/common/autoware_test_utils/test/test_mock_data_parser.cpp index f2b23cc43b07b..34218d48552e9 100644 --- a/common/autoware_test_utils/test/test_mock_data_parser.cpp +++ b/common/autoware_test_utils/test/test_mock_data_parser.cpp @@ -20,6 +20,8 @@ #include +#include + namespace autoware::test_utils { using tier4_planning_msgs::msg::PathWithLaneId; diff --git a/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp b/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp index e9189a6c84c2b..a08145f429c72 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp +++ b/common/autoware_traffic_light_recognition_marker_publisher/src/traffic_light_recognition_marker_publisher.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include diff --git a/common/autoware_traffic_light_utils/src/traffic_light_utils.cpp b/common/autoware_traffic_light_utils/src/traffic_light_utils.cpp index 4ba7e1c1d57d8..97d3081ceefdd 100644 --- a/common/autoware_traffic_light_utils/src/traffic_light_utils.cpp +++ b/common/autoware_traffic_light_utils/src/traffic_light_utils.cpp @@ -14,6 +14,8 @@ #include "autoware/traffic_light_utils/traffic_light_utils.hpp" +#include + namespace autoware::traffic_light_utils { diff --git a/common/autoware_trajectory/examples/example_trajectory_path_point.cpp b/common/autoware_trajectory/examples/example_trajectory_path_point.cpp index 777942654e5b2..fb1197e53ab67 100644 --- a/common/autoware_trajectory/examples/example_trajectory_path_point.cpp +++ b/common/autoware_trajectory/examples/example_trajectory_path_point.cpp @@ -19,6 +19,7 @@ #include +#include #include autoware_planning_msgs::msg::PathPoint path_point(double x, double y) diff --git a/common/autoware_trajectory/src/path_point.cpp b/common/autoware_trajectory/src/path_point.cpp index 4a2ac80b749bd..0806bcead53f3 100644 --- a/common/autoware_trajectory/src/path_point.cpp +++ b/common/autoware_trajectory/src/path_point.cpp @@ -18,6 +18,8 @@ #include +#include + namespace autoware::trajectory { diff --git a/common/autoware_trajectory/src/point.cpp b/common/autoware_trajectory/src/point.cpp index c7b9a6ab74a38..40c6c357e9ba5 100644 --- a/common/autoware_trajectory/src/point.cpp +++ b/common/autoware_trajectory/src/point.cpp @@ -22,6 +22,7 @@ #include #include #include +#include namespace autoware::trajectory { diff --git a/common/autoware_trajectory/test/test_trajectory_container.cpp b/common/autoware_trajectory/test/test_trajectory_container.cpp index 028d36d98a954..6f6d52107b348 100644 --- a/common/autoware_trajectory/test/test_trajectory_container.cpp +++ b/common/autoware_trajectory/test/test_trajectory_container.cpp @@ -15,6 +15,7 @@ #include +#include #include using Trajectory = autoware::trajectory::Trajectory; diff --git a/common/autoware_universe_utils/examples/example_lru_cache.cpp b/common/autoware_universe_utils/examples/example_lru_cache.cpp index 95decf8eb336d..6ddf5ec165529 100644 --- a/common/autoware_universe_utils/examples/example_lru_cache.cpp +++ b/common/autoware_universe_utils/examples/example_lru_cache.cpp @@ -17,6 +17,8 @@ #include #include #include +#include +#include using autoware::universe_utils::LRUCache; diff --git a/common/autoware_universe_utils/examples/example_polling_subscriber.cpp b/common/autoware_universe_utils/examples/example_polling_subscriber.cpp index d078da6df43af..b9a76356e07c4 100644 --- a/common/autoware_universe_utils/examples/example_polling_subscriber.cpp +++ b/common/autoware_universe_utils/examples/example_polling_subscriber.cpp @@ -18,6 +18,8 @@ #include +#include + // PublisherNode class definition class PublisherNode : public rclcpp::Node { diff --git a/common/autoware_universe_utils/src/geometry/alt_geometry.cpp b/common/autoware_universe_utils/src/geometry/alt_geometry.cpp index 0d6e608d8cd6d..848ecdd699ec5 100644 --- a/common/autoware_universe_utils/src/geometry/alt_geometry.cpp +++ b/common/autoware_universe_utils/src/geometry/alt_geometry.cpp @@ -14,6 +14,11 @@ #include "autoware/universe_utils/geometry/alt_geometry.hpp" +#include +#include +#include +#include + namespace autoware::universe_utils { // Alternatives for Boost.Geometry ---------------------------------------------------------------- diff --git a/common/autoware_universe_utils/src/geometry/ear_clipping.cpp b/common/autoware_universe_utils/src/geometry/ear_clipping.cpp index edc17b2dab120..f178a7e832511 100644 --- a/common/autoware_universe_utils/src/geometry/ear_clipping.cpp +++ b/common/autoware_universe_utils/src/geometry/ear_clipping.cpp @@ -14,6 +14,10 @@ #include "autoware/universe_utils/geometry/ear_clipping.hpp" +#include +#include +#include + namespace autoware::universe_utils { diff --git a/common/autoware_universe_utils/src/geometry/geometry.cpp b/common/autoware_universe_utils/src/geometry/geometry.cpp index 5fda8eb3f4ca4..e9aaccd055dad 100644 --- a/common/autoware_universe_utils/src/geometry/geometry.cpp +++ b/common/autoware_universe_utils/src/geometry/geometry.cpp @@ -22,6 +22,8 @@ #include +#include + namespace tf2 { void fromMsg(const geometry_msgs::msg::PoseStamped & msg, tf2::Stamped & out) diff --git a/common/autoware_universe_utils/src/geometry/random_concave_polygon.cpp b/common/autoware_universe_utils/src/geometry/random_concave_polygon.cpp index aa3c2afab321a..35819c0b119bf 100644 --- a/common/autoware_universe_utils/src/geometry/random_concave_polygon.cpp +++ b/common/autoware_universe_utils/src/geometry/random_concave_polygon.cpp @@ -22,7 +22,12 @@ #include #include +#include +#include +#include #include +#include +#include namespace autoware::universe_utils { diff --git a/common/autoware_universe_utils/src/geometry/sat_2d.cpp b/common/autoware_universe_utils/src/geometry/sat_2d.cpp index eae1de39bb589..a38fcbd3c3430 100644 --- a/common/autoware_universe_utils/src/geometry/sat_2d.cpp +++ b/common/autoware_universe_utils/src/geometry/sat_2d.cpp @@ -14,6 +14,8 @@ #include "autoware/universe_utils/geometry/sat_2d.hpp" +#include + namespace autoware::universe_utils::sat { diff --git a/common/autoware_universe_utils/src/math/trigonometry.cpp b/common/autoware_universe_utils/src/math/trigonometry.cpp index 2966f35bfe59e..5cfe1326323e5 100644 --- a/common/autoware_universe_utils/src/math/trigonometry.cpp +++ b/common/autoware_universe_utils/src/math/trigonometry.cpp @@ -18,6 +18,7 @@ #include "autoware/universe_utils/math/sin_table.hpp" #include +#include namespace autoware::universe_utils { diff --git a/common/autoware_universe_utils/src/ros/marker_helper.cpp b/common/autoware_universe_utils/src/ros/marker_helper.cpp index 0d360e2335df7..3370f7e05814a 100644 --- a/common/autoware_universe_utils/src/ros/marker_helper.cpp +++ b/common/autoware_universe_utils/src/ros/marker_helper.cpp @@ -14,6 +14,8 @@ #include "autoware/universe_utils/ros/marker_helper.hpp" +#include + namespace autoware::universe_utils { visualization_msgs::msg::Marker createDefaultMarker( diff --git a/common/autoware_universe_utils/src/system/time_keeper.cpp b/common/autoware_universe_utils/src/system/time_keeper.cpp index b6e82cbd2f58a..55901ce5b4987 100644 --- a/common/autoware_universe_utils/src/system/time_keeper.cpp +++ b/common/autoware_universe_utils/src/system/time_keeper.cpp @@ -19,8 +19,10 @@ #include +#include #include #include +#include namespace autoware::universe_utils { diff --git a/common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp index 90dfb1ede4701..9fa949cedb867 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp @@ -25,7 +25,10 @@ #include #include +#include +#include #include +#include constexpr double epsilon = 1e-6; diff --git a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp index 3202347cc8ac4..3e4b08c4cc272 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp @@ -29,7 +29,10 @@ #include #include +#include +#include #include +#include constexpr double epsilon = 1e-6; diff --git a/common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp b/common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp index 9df6f9bb2ffef..351cd252126cc 100644 --- a/common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp +++ b/common/autoware_universe_utils/test/src/ros/test_managed_transform_buffer.cpp @@ -21,6 +21,7 @@ #include #include +#include class TestManagedTransformBuffer : public ::testing::Test { diff --git a/common/autoware_universe_utils/test/src/ros/test_published_time_publisher.cpp b/common/autoware_universe_utils/test/src/ros/test_published_time_publisher.cpp index f9c0bd45c4fb4..7e4debfe59c2b 100644 --- a/common/autoware_universe_utils/test/src/ros/test_published_time_publisher.cpp +++ b/common/autoware_universe_utils/test/src/ros/test_published_time_publisher.cpp @@ -20,6 +20,10 @@ #include +#include +#include +#include + class PublishedTimePublisherWithSubscriptionTest : public ::testing::Test { protected: diff --git a/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp b/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp index ffefaed316b19..4491d79051059 100644 --- a/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp +++ b/common/autoware_universe_utils/test/src/system/test_time_keeper.cpp @@ -19,7 +19,9 @@ #include #include +#include #include +#include #include class TimeKeeperTest : public ::testing::Test diff --git a/common/autoware_vehicle_info_utils/src/vehicle_info.cpp b/common/autoware_vehicle_info_utils/src/vehicle_info.cpp index c1e762811ede3..c0a4c240ba44a 100644 --- a/common/autoware_vehicle_info_utils/src/vehicle_info.cpp +++ b/common/autoware_vehicle_info_utils/src/vehicle_info.cpp @@ -16,6 +16,8 @@ #include +#include + namespace autoware::vehicle_info_utils { autoware::universe_utils::LinearRing2d VehicleInfo::createFootprint(const double margin) const diff --git a/common/autoware_vehicle_info_utils/test/test_vehicle_info_utils.cpp b/common/autoware_vehicle_info_utils/test/test_vehicle_info_utils.cpp index 3ad19ba9cab35..ea660208da2be 100644 --- a/common/autoware_vehicle_info_utils/test/test_vehicle_info_utils.cpp +++ b/common/autoware_vehicle_info_utils/test/test_vehicle_info_utils.cpp @@ -17,6 +17,8 @@ #include +#include + class VehicleInfoUtilTest : public ::testing::Test { protected: diff --git a/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp b/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp index ef52977cb7e73..cae9660b51266 100644 --- a/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp +++ b/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp @@ -21,6 +21,8 @@ #include #include +#include + namespace rviz_plugins { BagTimeManagerPanel::BagTimeManagerPanel(QWidget * parent) : rviz_common::Panel(parent) diff --git a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp index d427f63628d69..bcf9d774200e6 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp @@ -22,6 +22,8 @@ #include #include +#include + namespace rviz_plugins { PoseHistory::PoseHistory() : last_stamp_(0, 0, RCL_ROS_TIME) diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp index 391ebdc0c1c77..a54856122ffc9 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp @@ -22,6 +22,8 @@ #include #include +#include + #define EIGEN_MPL2_ONLY #include #include diff --git a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp index 42f36ed6f4c08..276206075b6eb 100644 --- a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp +++ b/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp @@ -27,6 +27,8 @@ #include +#include + namespace rviz_plugins { PoseWithCovarianceHistory::PoseWithCovarianceHistory() : last_stamp_(0, 0, RCL_ROS_TIME) diff --git a/common/tier4_planning_rviz_plugin/src/path/display.cpp b/common/tier4_planning_rviz_plugin/src/path/display.cpp index 342e72d66c5f9..869f0c4d91793 100644 --- a/common/tier4_planning_rviz_plugin/src/path/display.cpp +++ b/common/tier4_planning_rviz_plugin/src/path/display.cpp @@ -16,6 +16,10 @@ #include +#include +#include +#include + namespace rviz_plugins { AutowarePathWithLaneIdDisplay::AutowarePathWithLaneIdDisplay() diff --git a/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp b/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp index b525608a65625..ddb55a253b1cf 100644 --- a/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp +++ b/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp @@ -20,6 +20,9 @@ #include #include +#include +#include + namespace { std::string uuid_to_string(const unique_identifier_msgs::msg::UUID & u) diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp index fab40fe5a2214..78ddfae57cd0c 100644 --- a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp @@ -24,6 +24,7 @@ #include #include +#include #include #include From 06e202fee2f4b61eed8f095a028c3f1658546c91 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:13:15 +0300 Subject: [PATCH 221/273] fix(cpplint): include what you use - control (#9565) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- control/autoware_autonomous_emergency_braking/src/node.cpp | 3 +++ control/autoware_autonomous_emergency_braking/src/utils.cpp | 2 ++ control/autoware_autonomous_emergency_braking/test/test.cpp | 1 + control/autoware_collision_detector/src/node.cpp | 6 ++++++ .../autoware_control_validator/src/control_validator.cpp | 1 + .../test/test_control_validator.cpp | 1 + .../lane_departure_checker_node/lane_departure_checker.cpp | 1 + .../src/lane_departure_checker_node/utils.cpp | 2 ++ .../test/test_calc_max_search_length_for_boundaries.cpp | 3 +++ .../test/test_calc_trajectory_deviation.cpp | 3 +++ .../test/test_create_vehicle_footprints.cpp | 3 +++ .../test/test_resample_trajectory.cpp | 3 +++ .../autoware_mpc_lateral_controller/src/lowpass_filter.cpp | 1 + control/autoware_mpc_lateral_controller/src/mpc.cpp | 4 ++++ .../autoware_mpc_lateral_controller/src/mpc_trajectory.cpp | 2 ++ control/autoware_mpc_lateral_controller/src/mpc_utils.cpp | 2 ++ .../test/test_obstacle_collision_checker.cpp | 1 + .../autoware_operation_mode_transition_manager/src/data.cpp | 2 ++ .../autoware_operation_mode_transition_manager/src/node.cpp | 2 ++ .../src/state.cpp | 2 ++ .../src/longitudinal_controller_utils.cpp | 2 ++ .../autoware_pure_pursuit_lateral_controller.cpp | 1 + .../src/autoware_pure_pursuit_core/interpolate.cpp | 2 ++ .../src/proxima_calc.cpp | 2 ++ .../test/test_controller_node.cpp | 1 + .../autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp | 1 + .../test/src/test_filter_in_vehicle_cmd_gate_node.cpp | 2 ++ .../src/control_performance_analysis_core.cpp | 1 + .../src/predicted_path_checker_node/collision_checker.cpp | 1 + .../src/predicted_path_checker_node/utils.cpp | 2 ++ 30 files changed, 60 insertions(+) diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 21a690cd0eec3..eb0884e4f344e 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -43,10 +43,13 @@ #include #include +#include #include #include #include +#include #include +#include #include #ifdef ROS_DISTRO_GALACTIC #include diff --git a/control/autoware_autonomous_emergency_braking/src/utils.cpp b/control/autoware_autonomous_emergency_braking/src/utils.cpp index 9b9d09777e09e..abd203dee2a02 100644 --- a/control/autoware_autonomous_emergency_braking/src/utils.cpp +++ b/control/autoware_autonomous_emergency_braking/src/utils.cpp @@ -17,6 +17,8 @@ #include #include +#include +#include namespace autoware::motion::control::autonomous_emergency_braking::utils { diff --git a/control/autoware_autonomous_emergency_braking/test/test.cpp b/control/autoware_autonomous_emergency_braking/test/test.cpp index 360e6f9877e06..1845ab4074fad 100644 --- a/control/autoware_autonomous_emergency_braking/test/test.cpp +++ b/control/autoware_autonomous_emergency_braking/test/test.cpp @@ -31,6 +31,7 @@ #include #include #include +#include namespace autoware::motion::control::autonomous_emergency_braking::test { diff --git a/control/autoware_collision_detector/src/node.cpp b/control/autoware_collision_detector/src/node.cpp index cfb9e5bfc6dbb..77d6d76c08b0a 100644 --- a/control/autoware_collision_detector/src/node.cpp +++ b/control/autoware_collision_detector/src/node.cpp @@ -29,6 +29,12 @@ #include #include +#include +#include +#include +#include +#include + #define EIGEN_MPL2_ONLY #include #include diff --git a/control/autoware_control_validator/src/control_validator.cpp b/control/autoware_control_validator/src/control_validator.cpp index d51282cb33bb3..0c16fae065939 100644 --- a/control/autoware_control_validator/src/control_validator.cpp +++ b/control/autoware_control_validator/src/control_validator.cpp @@ -23,6 +23,7 @@ #include #include #include +#include namespace autoware::control_validator { diff --git a/control/autoware_control_validator/test/test_control_validator.cpp b/control/autoware_control_validator/test/test_control_validator.cpp index c4d5b04fa920c..76ba5b7894365 100644 --- a/control/autoware_control_validator/test/test_control_validator.cpp +++ b/control/autoware_control_validator/test/test_control_validator.cpp @@ -24,6 +24,7 @@ #include #include +#include #include using autoware_planning_msgs::msg::Trajectory; diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index a1ef24e32543f..1c75b3552df67 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -26,6 +26,7 @@ #include #include +#include #include using autoware::universe_utils::LinearRing2d; diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp index 19ea23ccd19da..5613b767a9fd0 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp @@ -19,6 +19,8 @@ #include +#include + namespace { struct FootprintMargin diff --git a/control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp b/control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp index 1632f41f35153..2a7cef58e381f 100644 --- a/control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp +++ b/control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp @@ -18,6 +18,9 @@ #include +#include +#include + using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; diff --git a/control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp b/control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp index a0f141e9639a9..ccb85d1a0fec1 100644 --- a/control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp +++ b/control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp @@ -18,6 +18,9 @@ #include +#include +#include + using autoware::universe_utils::PoseDeviation; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; diff --git a/control/autoware_lane_departure_checker/test/test_create_vehicle_footprints.cpp b/control/autoware_lane_departure_checker/test/test_create_vehicle_footprints.cpp index 6189d8803a3ea..e17e2bc697272 100644 --- a/control/autoware_lane_departure_checker/test/test_create_vehicle_footprints.cpp +++ b/control/autoware_lane_departure_checker/test/test_create_vehicle_footprints.cpp @@ -18,6 +18,9 @@ #include +#include +#include + using autoware::universe_utils::LinearRing2d; using autoware_planning_msgs::msg::TrajectoryPoint; using geometry_msgs::msg::PoseWithCovariance; diff --git a/control/autoware_lane_departure_checker/test/test_resample_trajectory.cpp b/control/autoware_lane_departure_checker/test/test_resample_trajectory.cpp index 67fe69323584e..214a165660225 100644 --- a/control/autoware_lane_departure_checker/test/test_resample_trajectory.cpp +++ b/control/autoware_lane_departure_checker/test/test_resample_trajectory.cpp @@ -18,6 +18,9 @@ #include +#include +#include + using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; diff --git a/control/autoware_mpc_lateral_controller/src/lowpass_filter.cpp b/control/autoware_mpc_lateral_controller/src/lowpass_filter.cpp index 4a056c351208b..379ec0b614712 100644 --- a/control/autoware_mpc_lateral_controller/src/lowpass_filter.cpp +++ b/control/autoware_mpc_lateral_controller/src/lowpass_filter.cpp @@ -14,6 +14,7 @@ #include "autoware/mpc_lateral_controller/lowpass_filter.hpp" +#include #include namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/autoware_mpc_lateral_controller/src/mpc.cpp b/control/autoware_mpc_lateral_controller/src/mpc.cpp index 3c3496080b597..4c3c8bec9b12e 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc.cpp @@ -23,7 +23,11 @@ #include #include +#include #include +#include +#include +#include namespace autoware::motion::control::mpc_lateral_controller { diff --git a/control/autoware_mpc_lateral_controller/src/mpc_trajectory.cpp b/control/autoware_mpc_lateral_controller/src/mpc_trajectory.cpp index 842689527c847..0156d7af138bc 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_trajectory.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_trajectory.cpp @@ -14,6 +14,8 @@ #include "autoware/mpc_lateral_controller/mpc_trajectory.hpp" +#include + namespace autoware::motion::control::mpc_lateral_controller { void MPCTrajectory::push_back( diff --git a/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp b/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp index 820ee848c17fe..e8bc981a8ade8 100644 --- a/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp +++ b/control/autoware_mpc_lateral_controller/src/mpc_utils.cpp @@ -21,8 +21,10 @@ #include "autoware/universe_utils/math/normalization.hpp" #include +#include #include #include +#include #include namespace autoware::motion::control::mpc_lateral_controller diff --git a/control/autoware_obstacle_collision_checker/test/test_obstacle_collision_checker.cpp b/control/autoware_obstacle_collision_checker/test/test_obstacle_collision_checker.cpp index 97b26162812ef..789d5602b2414 100644 --- a/control/autoware_obstacle_collision_checker/test/test_obstacle_collision_checker.cpp +++ b/control/autoware_obstacle_collision_checker/test/test_obstacle_collision_checker.cpp @@ -29,6 +29,7 @@ #include #include +#include namespace { diff --git a/control/autoware_operation_mode_transition_manager/src/data.cpp b/control/autoware_operation_mode_transition_manager/src/data.cpp index 1fac496f3c71c..48200d75fe2cb 100644 --- a/control/autoware_operation_mode_transition_manager/src/data.cpp +++ b/control/autoware_operation_mode_transition_manager/src/data.cpp @@ -14,6 +14,8 @@ #include "data.hpp" +#include + namespace autoware::operation_mode_transition_manager { diff --git a/control/autoware_operation_mode_transition_manager/src/node.cpp b/control/autoware_operation_mode_transition_manager/src/node.cpp index d0c7f303fca04..25c048b0540fa 100644 --- a/control/autoware_operation_mode_transition_manager/src/node.cpp +++ b/control/autoware_operation_mode_transition_manager/src/node.cpp @@ -16,6 +16,8 @@ #include +#include + namespace autoware::operation_mode_transition_manager { diff --git a/control/autoware_operation_mode_transition_manager/src/state.cpp b/control/autoware_operation_mode_transition_manager/src/state.cpp index 31cd32e6311a9..5969e6b9fb03d 100644 --- a/control/autoware_operation_mode_transition_manager/src/state.cpp +++ b/control/autoware_operation_mode_transition_manager/src/state.cpp @@ -22,6 +22,8 @@ #include #include +#include +#include namespace autoware::operation_mode_transition_manager { diff --git a/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp b/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp index 134de5d1ac8bd..fe500d2551623 100644 --- a/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp +++ b/control/autoware_pid_longitudinal_controller/src/longitudinal_controller_utils.cpp @@ -19,6 +19,8 @@ #include // NOLINT +#include + #ifdef ROS_DISTRO_GALACTIC #include "tf2_geometry_msgs/tf2_geometry_msgs.h" #else diff --git a/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp b/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp index 085addbe17fc9..f3a7bc3c1333d 100644 --- a/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp +++ b/control/autoware_pure_pursuit/src/autoware_pure_pursuit/autoware_pure_pursuit_lateral_controller.cpp @@ -39,6 +39,7 @@ #include #include #include +#include namespace { diff --git a/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/interpolate.cpp b/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/interpolate.cpp index 9b68594f167e8..6688ed6a9f27d 100644 --- a/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/interpolate.cpp +++ b/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/interpolate.cpp @@ -15,6 +15,8 @@ #include "autoware/pure_pursuit/util/interpolate.hpp" #include +#include +#include #include namespace autoware::pure_pursuit diff --git a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/src/proxima_calc.cpp b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/src/proxima_calc.cpp index 8dbee65804237..daa054af31627 100644 --- a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/src/proxima_calc.cpp +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/src/proxima_calc.cpp @@ -19,7 +19,9 @@ #include #include +#include #include +#include namespace py = pybind11; Eigen::VectorXd tanh(const Eigen::VectorXd & v) diff --git a/control/autoware_trajectory_follower_node/test/test_controller_node.cpp b/control/autoware_trajectory_follower_node/test/test_controller_node.cpp index 40e4366d9aa17..0b1dac644a8ab 100644 --- a/control/autoware_trajectory_follower_node/test/test_controller_node.cpp +++ b/control/autoware_trajectory_follower_node/test/test_controller_node.cpp @@ -30,6 +30,7 @@ #include "geometry_msgs/msg/transform_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" +#include #include #include 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 a18571144792a..c540f48dfc186 100644 --- a/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp +++ b/control/autoware_vehicle_cmd_gate/src/vehicle_cmd_filter.cpp @@ -16,6 +16,7 @@ #include #include +#include namespace autoware::vehicle_cmd_gate { diff --git a/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp b/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp index 66dde51780ffa..9b403e2f8ed74 100644 --- a/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp +++ b/control/autoware_vehicle_cmd_gate/test/src/test_filter_in_vehicle_cmd_gate_node.cpp @@ -17,9 +17,11 @@ #include +#include #include #include #include +#include #include #include diff --git a/control/control_performance_analysis/src/control_performance_analysis_core.cpp b/control/control_performance_analysis/src/control_performance_analysis_core.cpp index 769593ac34d09..08f736dd0b630 100644 --- a/control/control_performance_analysis/src/control_performance_analysis_core.cpp +++ b/control/control_performance_analysis/src/control_performance_analysis_core.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include #include diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp index 7771f59d15454..2841888b61bcc 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/collision_checker.cpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include diff --git a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp index 4b6d0755db25f..12e38fd9968ab 100644 --- a/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp +++ b/control/predicted_path_checker/src/predicted_path_checker_node/utils.cpp @@ -18,6 +18,8 @@ #include #include +#include + namespace utils { From 1bb1ffe0889b561e7692c628b8f2b5e3df953f96 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:13:32 +0300 Subject: [PATCH 222/273] fix(cpplint): include what you use - evaluator (#9566) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../test/test_control_evaluator_node.cpp | 1 + .../src/planning_evaluator_node.cpp | 1 + .../test/test_planning_evaluator_node.cpp | 1 + .../test/test_kinematic_evaluator_node.cpp | 1 + .../test/test_localization_evaluator_node.cpp | 1 + .../src/metrics/detection_count.cpp | 5 +++++ .../src/metrics/deviation_metrics.cpp | 2 ++ .../perception_online_evaluator/src/utils/marker_utils.cpp | 3 +++ .../src/utils/objects_filtering.cpp | 3 +++ .../test/test_perception_online_evaluator_node.cpp | 2 ++ .../scenario_simulator_v2_adapter/src/converter_node.cpp | 2 ++ 11 files changed, 22 insertions(+) diff --git a/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp b/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp index 728cef03901a8..9098ce5667424 100644 --- a/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp +++ b/evaluator/autoware_control_evaluator/test/test_control_evaluator_node.cpp @@ -28,6 +28,7 @@ #include +#include #include #include #include diff --git a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp index da23c202312d7..a61e56cd532ad 100644 --- a/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/src/planning_evaluator_node.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include diff --git a/evaluator/autoware_planning_evaluator/test/test_planning_evaluator_node.cpp b/evaluator/autoware_planning_evaluator/test/test_planning_evaluator_node.cpp index 1b29edfb9b353..f202bb4ab0e6f 100644 --- a/evaluator/autoware_planning_evaluator/test/test_planning_evaluator_node.cpp +++ b/evaluator/autoware_planning_evaluator/test/test_planning_evaluator_node.cpp @@ -27,6 +27,7 @@ #include "boost/lexical_cast.hpp" +#include #include #include #include diff --git a/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp b/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp index 51e6113aea999..769f98416848f 100644 --- a/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp +++ b/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp @@ -26,6 +26,7 @@ #include "boost/lexical_cast.hpp" +#include #include #include #include diff --git a/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp b/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp index cd6a7b80fd35b..6ab428c6fb578 100644 --- a/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp +++ b/evaluator/localization_evaluator/test/test_localization_evaluator_node.cpp @@ -27,6 +27,7 @@ #include "boost/lexical_cast.hpp" +#include #include #include #include diff --git a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp index ab69ea9cb8c7b..4a1d97aeeb90b 100644 --- a/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp +++ b/evaluator/perception_online_evaluator/src/metrics/detection_count.cpp @@ -20,6 +20,11 @@ #include +#include +#include +#include +#include + namespace perception_diagnostics { namespace metrics diff --git a/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp b/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp index 8570cf246f430..292fc9cd65a17 100644 --- a/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp +++ b/evaluator/perception_online_evaluator/src/metrics/deviation_metrics.cpp @@ -19,6 +19,8 @@ #include +#include + namespace perception_diagnostics { namespace metrics diff --git a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp index 0c6d1cac4246e..7489447ccb47e 100644 --- a/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp +++ b/evaluator/perception_online_evaluator/src/utils/marker_utils.cpp @@ -24,7 +24,10 @@ #include #include +#include #include +#include +#include namespace marker_utils { diff --git a/evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp b/evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp index 6ffb80eb40b59..13bd820f18cec 100644 --- a/evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp +++ b/evaluator/perception_online_evaluator/src/utils/objects_filtering.cpp @@ -14,6 +14,9 @@ #include "perception_online_evaluator/utils/objects_filtering.hpp" +#include +#include + namespace perception_diagnostics { namespace filter diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index 5b23f6d37a1d4..ffefee835f933 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -29,6 +29,8 @@ #include #include +#include +#include #include #include #include diff --git a/evaluator/scenario_simulator_v2_adapter/src/converter_node.cpp b/evaluator/scenario_simulator_v2_adapter/src/converter_node.cpp index 98d36327793fe..4c0464b8b2d41 100644 --- a/evaluator/scenario_simulator_v2_adapter/src/converter_node.cpp +++ b/evaluator/scenario_simulator_v2_adapter/src/converter_node.cpp @@ -15,6 +15,8 @@ #include "scenario_simulator_v2_adapter/converter_node.hpp" #include +#include +#include namespace { From 6ddf94c1f49416cd2cbee420419c461cc1ce475c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:13:45 +0300 Subject: [PATCH 223/273] fix(cpplint): include what you use - localization (#9567) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- localization/autoware_ekf_localizer/src/ekf_localizer.cpp | 1 + .../test/test_aged_object_queue.cpp | 2 ++ .../autoware_ekf_localizer/test/test_diagnostics.cpp | 3 +++ localization/autoware_ekf_localizer/test/test_numeric.cpp | 2 ++ .../src/geo_pose_projector.cpp | 2 ++ .../src/ar_tag_based_localizer.cpp | 4 ++++ .../autoware_ar_tag_based_localizer/test/test.cpp | 1 + .../autoware_landmark_manager/src/landmark_manager.cpp | 4 ++++ .../src/lidar_marker_localizer.cpp | 2 ++ .../autoware_localization_util/src/covariance_ellipse.cpp | 2 ++ .../src/tree_structured_parzen_estimator.cpp | 3 +++ localization/autoware_localization_util/src/util_func.cpp | 3 +++ localization/autoware_localization_util/test/test_tpe.cpp | 6 ++++++ .../autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h | 1 + .../autoware_ndt_scan_matcher/src/map_update_module.cpp | 3 +++ .../src/ndt_omp/estimate_covariance.cpp | 4 ++++ .../src/ndt_scan_matcher_core.cpp | 5 +++++ localization/autoware_ndt_scan_matcher/src/particle.cpp | 2 ++ .../autoware_ndt_scan_matcher/test/test_fixture.hpp | 1 + .../src/pose_covariance_modifier.cpp | 2 ++ .../example_rule/src/rule_helper/pose_estimator_area.cpp | 2 ++ .../example_rule/src/switch_rule/pcd_map_based_rule.cpp | 3 +++ .../src/switch_rule/vector_map_based_rule.cpp | 4 ++++ .../example_rule/test/test_pcd_map_based_rule.cpp | 1 + .../example_rule/test/test_rule_helper.cpp | 2 ++ .../example_rule/test/test_vector_map_based_rule.cpp | 1 + .../src/pose_estimator_arbiter_core.cpp | 8 ++++++++ .../src/switch_rule/enable_all_rule.cpp | 1 + .../autoware_pose_initializer/src/localization_module.cpp | 1 + .../test/test_copy_vector_to_array.cpp | 2 ++ .../src/pose_instability_detector.cpp | 2 ++ .../autoware_pose_instability_detector/test/test.cpp | 1 + .../yabloc/yabloc_common/src/camera_info_subscriber.cpp | 2 ++ localization/yabloc/yabloc_common/src/cv_decompress.cpp | 2 ++ .../src/ground_server/ground_server_core.cpp | 5 +++++ .../yabloc_common/src/ground_server/polygon_operation.cpp | 2 ++ .../src/ll2_decomposer/ll2_decomposer_core.cpp | 4 ++++ .../yabloc/yabloc_common/src/static_tf_subscriber.cpp | 3 +++ .../src/graph_segment/graph_segment_core.cpp | 5 +++++ .../src/graph_segment/similar_area_searcher.cpp | 3 +++ .../src/lanelet2_overlay/lanelet2_overlay_core.cpp | 3 +++ .../line_segment_detector/line_segment_detector_core.cpp | 2 ++ .../src/segment_filter/segment_filter_core.cpp | 5 +++++ .../src/undistort/undistort_node.cpp | 2 ++ .../ll2_cost_map/hierarchical_cost_map.hpp | 1 + .../camera_corrector/camera_particle_corrector_core.cpp | 3 +++ .../src/camera_corrector/filter_line_segments.cpp | 2 ++ .../yabloc/yabloc_particle_filter/src/common/mean.cpp | 1 + .../src/common/particle_visualize_node.cpp | 2 ++ .../yabloc_particle_filter/src/common/visualize.cpp | 2 ++ .../src/correction/abstract_corrector.cpp | 4 ++++ .../src/ll2_cost_map/direct_cost_map.cpp | 3 +++ .../src/ll2_cost_map/hierarchical_cost_map.cpp | 2 ++ .../yabloc_particle_filter/src/prediction/predictor.cpp | 2 ++ .../yabloc_particle_filter/src/prediction/resampler.cpp | 1 + .../src/camera/camera_pose_initializer_core.cpp | 4 ++++ .../yabloc_pose_initializer/src/camera/lane_image.cpp | 3 +++ .../yabloc_pose_initializer/src/camera/marker_module.cpp | 3 +++ .../src/camera/projector_module.cpp | 2 ++ .../src/camera/semantic_segmentation.cpp | 2 ++ 60 files changed, 156 insertions(+) diff --git a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp index 7e2606cdc3860..d34be2a537ef1 100644 --- a/localization/autoware_ekf_localizer/src/ekf_localizer.cpp +++ b/localization/autoware_ekf_localizer/src/ekf_localizer.cpp @@ -33,6 +33,7 @@ #include #include #include +#include namespace autoware::ekf_localizer { diff --git a/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp b/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp index 9cf56b80bb79a..dc9ef008335ed 100644 --- a/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp +++ b/localization/autoware_ekf_localizer/test/test_aged_object_queue.cpp @@ -16,6 +16,8 @@ #include +#include + namespace autoware::ekf_localizer { diff --git a/localization/autoware_ekf_localizer/test/test_diagnostics.cpp b/localization/autoware_ekf_localizer/test/test_diagnostics.cpp index 979f4c75deb84..165102adec1d7 100644 --- a/localization/autoware_ekf_localizer/test/test_diagnostics.cpp +++ b/localization/autoware_ekf_localizer/test/test_diagnostics.cpp @@ -16,6 +16,9 @@ #include +#include +#include + namespace autoware::ekf_localizer { diff --git a/localization/autoware_ekf_localizer/test/test_numeric.cpp b/localization/autoware_ekf_localizer/test/test_numeric.cpp index 8071804f48304..080ce01f31770 100644 --- a/localization/autoware_ekf_localizer/test/test_numeric.cpp +++ b/localization/autoware_ekf_localizer/test/test_numeric.cpp @@ -18,6 +18,8 @@ #include +#include + namespace autoware::ekf_localizer { diff --git a/localization/autoware_geo_pose_projector/src/geo_pose_projector.cpp b/localization/autoware_geo_pose_projector/src/geo_pose_projector.cpp index c3bf074f73aeb..0db808257f639 100644 --- a/localization/autoware_geo_pose_projector/src/geo_pose_projector.cpp +++ b/localization/autoware_geo_pose_projector/src/geo_pose_projector.cpp @@ -17,6 +17,8 @@ #include #include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp index 2418cf3f5dd1c..9d2a8bf814694 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/src/ar_tag_based_localizer.cpp @@ -51,6 +51,10 @@ #include #include +#include +#include +#include + #if __has_include() #include // for ROS 2 Jazzy or newer #else diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/test/test.cpp b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/test/test.cpp index 295737ed723a5..5c2cbf3957de0 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/test/test.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/test/test.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include #include diff --git a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp index 04823a71febe9..a4ab83cde6dfa 100644 --- a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/src/landmark_manager.cpp @@ -24,6 +24,10 @@ #include #include +#include +#include +#include + namespace landmark_manager { diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp index 947ba02402697..2faf2d19168a5 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp @@ -31,9 +31,11 @@ #include #include #include +#include #include #include #include +#include namespace autoware::lidar_marker_localizer { diff --git a/localization/autoware_localization_util/src/covariance_ellipse.cpp b/localization/autoware_localization_util/src/covariance_ellipse.cpp index 4a7d71909fb7a..847f89e0da9b3 100644 --- a/localization/autoware_localization_util/src/covariance_ellipse.cpp +++ b/localization/autoware_localization_util/src/covariance_ellipse.cpp @@ -15,6 +15,8 @@ #include "autoware/localization_util/covariance_ellipse.hpp" #include + +#include #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp b/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp index 064b33ebe3ad9..e9f0318d1e06d 100644 --- a/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp +++ b/localization/autoware_localization_util/src/tree_structured_parzen_estimator.cpp @@ -17,7 +17,10 @@ #include #include #include +#include #include +#include +#include namespace autoware::localization_util { diff --git a/localization/autoware_localization_util/src/util_func.cpp b/localization/autoware_localization_util/src/util_func.cpp index 6b019f7750471..17187a8d732f0 100644 --- a/localization/autoware_localization_util/src/util_func.cpp +++ b/localization/autoware_localization_util/src/util_func.cpp @@ -16,6 +16,9 @@ #include "autoware/localization_util/matrix_type.hpp" +#include +#include + namespace autoware::localization_util { // ref by http://takacity.blog.fc2.com/blog-entry-69.html diff --git a/localization/autoware_localization_util/test/test_tpe.cpp b/localization/autoware_localization_util/test/test_tpe.cpp index 6cbe3c2a62571..2d71a385246b7 100644 --- a/localization/autoware_localization_util/test/test_tpe.cpp +++ b/localization/autoware_localization_util/test/test_tpe.cpp @@ -16,6 +16,12 @@ #include +#include +#include +#include +#include +#include + using TreeStructuredParzenEstimator = autoware::localization_util::TreeStructuredParzenEstimator; TEST(TreeStructuredParzenEstimatorTest, TPE_is_better_than_random_search_on_sphere_function) diff --git a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h index 00c567775a6bf..b7c9877739123 100644 --- a/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h +++ b/localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_omp/multigrid_ndt_omp.h @@ -67,6 +67,7 @@ #include +#include #include #include diff --git a/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp b/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp index 31e0ae2eb1a59..25b51b55aebd7 100644 --- a/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp +++ b/localization/autoware_ndt_scan_matcher/src/map_update_module.cpp @@ -14,6 +14,9 @@ #include "autoware/ndt_scan_matcher/map_update_module.hpp" +#include +#include + namespace autoware::ndt_scan_matcher { diff --git a/localization/autoware_ndt_scan_matcher/src/ndt_omp/estimate_covariance.cpp b/localization/autoware_ndt_scan_matcher/src/ndt_omp/estimate_covariance.cpp index 3c6e8a3d5d2f0..d8a576a86879b 100644 --- a/localization/autoware_ndt_scan_matcher/src/ndt_omp/estimate_covariance.cpp +++ b/localization/autoware_ndt_scan_matcher/src/ndt_omp/estimate_covariance.cpp @@ -14,8 +14,12 @@ #include "autoware/ndt_scan_matcher/ndt_omp/estimate_covariance.hpp" +#include #include #include +#include +#include +#include namespace pclomp { diff --git a/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index a316c8fa346b9..a1871023d525b 100644 --- a/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -25,6 +25,11 @@ #include +#include +#include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/localization/autoware_ndt_scan_matcher/src/particle.cpp b/localization/autoware_ndt_scan_matcher/src/particle.cpp index a5db875fc3ff7..7211d612b7a21 100644 --- a/localization/autoware_ndt_scan_matcher/src/particle.cpp +++ b/localization/autoware_ndt_scan_matcher/src/particle.cpp @@ -15,6 +15,8 @@ #include "autoware/ndt_scan_matcher/particle.hpp" #include "autoware/localization_util/util_func.hpp" + +#include namespace autoware::ndt_scan_matcher { diff --git a/localization/autoware_ndt_scan_matcher/test/test_fixture.hpp b/localization/autoware_ndt_scan_matcher/test/test_fixture.hpp index b0b7dfe50b4ed..f82bb5fd03fea 100644 --- a/localization/autoware_ndt_scan_matcher/test/test_fixture.hpp +++ b/localization/autoware_ndt_scan_matcher/test/test_fixture.hpp @@ -28,6 +28,7 @@ #include #include +#include #include #include #include diff --git a/localization/autoware_pose_covariance_modifier/src/pose_covariance_modifier.cpp b/localization/autoware_pose_covariance_modifier/src/pose_covariance_modifier.cpp index 53d6ecb244f3e..1fa24c7b4f99c 100644 --- a/localization/autoware_pose_covariance_modifier/src/pose_covariance_modifier.cpp +++ b/localization/autoware_pose_covariance_modifier/src/pose_covariance_modifier.cpp @@ -21,6 +21,8 @@ #include #include +#include + namespace autoware::pose_covariance_modifier { using PoseSource = PoseCovarianceModifierNode::PoseSource; diff --git a/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.cpp index 41ad45430d238..b2e06118b4569 100644 --- a/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/rule_helper/pose_estimator_area.cpp @@ -23,6 +23,8 @@ #include #include +#include +#include #include #include diff --git a/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.cpp index cc5414ebd0a68..023b49c854621 100644 --- a/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/pcd_map_based_rule.cpp @@ -16,6 +16,9 @@ #include +#include +#include +#include #include namespace autoware::pose_estimator_arbiter::switch_rule diff --git a/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.cpp index 58cf9ab09e9a7..47eb67b1914ce 100644 --- a/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/src/switch_rule/vector_map_based_rule.cpp @@ -16,6 +16,10 @@ #include +#include +#include +#include +#include #include namespace autoware::pose_estimator_arbiter::switch_rule diff --git a/localization/autoware_pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp index 0d1f245123806..27ca4715fd0f1 100644 --- a/localization/autoware_pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_pcd_map_based_rule.cpp @@ -17,6 +17,7 @@ #include #include +#include #include class PcdMapBasedRuleMockNode : public ::testing::Test diff --git a/localization/autoware_pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp index 10833b5498b89..6925a424cac6c 100644 --- a/localization/autoware_pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_rule_helper.cpp @@ -26,6 +26,8 @@ #include #include +#include +#include #include class RuleHelperMockNode : public ::testing::Test diff --git a/localization/autoware_pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp index 9d537f2048176..e57956b6afae3 100644 --- a/localization/autoware_pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/example_rule/test/test_vector_map_based_rule.cpp @@ -22,6 +22,7 @@ #include #include +#include #include class VectorMapBasedRuleMockNode : public ::testing::Test diff --git a/localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter_core.cpp b/localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter_core.cpp index 9108d44e82fb5..c62c533f23093 100644 --- a/localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter_core.cpp +++ b/localization/autoware_pose_estimator_arbiter/src/pose_estimator_arbiter_core.cpp @@ -22,6 +22,14 @@ #include +#include +#include +#include +#include +#include +#include +#include + namespace autoware::pose_estimator_arbiter { // Parses ros param to get the estimator set that is running diff --git a/localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.cpp b/localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.cpp index 9767e9ef4fba4..22896d6b8f93b 100644 --- a/localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.cpp +++ b/localization/autoware_pose_estimator_arbiter/src/switch_rule/enable_all_rule.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include diff --git a/localization/autoware_pose_initializer/src/localization_module.cpp b/localization/autoware_pose_initializer/src/localization_module.cpp index c6b57dd83bc97..e3fdeec6934fe 100644 --- a/localization/autoware_pose_initializer/src/localization_module.cpp +++ b/localization/autoware_pose_initializer/src/localization_module.cpp @@ -19,6 +19,7 @@ #include #include +#include namespace autoware::pose_initializer { diff --git a/localization/autoware_pose_initializer/test/test_copy_vector_to_array.cpp b/localization/autoware_pose_initializer/test/test_copy_vector_to_array.cpp index 6205eb3b53864..99a07a56c22f7 100644 --- a/localization/autoware_pose_initializer/test/test_copy_vector_to_array.cpp +++ b/localization/autoware_pose_initializer/test/test_copy_vector_to_array.cpp @@ -16,6 +16,8 @@ #include +#include + TEST(CopyVectorToArray, CopyAllElements) { const std::vector vector{0, 1, 2, 3, 4}; diff --git a/localization/autoware_pose_instability_detector/src/pose_instability_detector.cpp b/localization/autoware_pose_instability_detector/src/pose_instability_detector.cpp index 36aa4f6d7d73e..d191ec2a3bb22 100644 --- a/localization/autoware_pose_instability_detector/src/pose_instability_detector.cpp +++ b/localization/autoware_pose_instability_detector/src/pose_instability_detector.cpp @@ -22,8 +22,10 @@ #include #include +#include #include #include +#include namespace autoware::pose_instability_detector { diff --git a/localization/autoware_pose_instability_detector/test/test.cpp b/localization/autoware_pose_instability_detector/test/test.cpp index bd663a2406903..14ca03e4c6f40 100644 --- a/localization/autoware_pose_instability_detector/test/test.cpp +++ b/localization/autoware_pose_instability_detector/test/test.cpp @@ -21,6 +21,7 @@ #include #include +#include #include #include #include diff --git a/localization/yabloc/yabloc_common/src/camera_info_subscriber.cpp b/localization/yabloc/yabloc_common/src/camera_info_subscriber.cpp index 222389c32ef31..118bc3cb634c3 100644 --- a/localization/yabloc/yabloc_common/src/camera_info_subscriber.cpp +++ b/localization/yabloc/yabloc_common/src/camera_info_subscriber.cpp @@ -14,6 +14,8 @@ #include "yabloc_common/camera_info_subscriber.hpp" +#include + namespace yabloc::common { CameraInfoSubscriber::CameraInfoSubscriber(rclcpp::Node * node) diff --git a/localization/yabloc/yabloc_common/src/cv_decompress.cpp b/localization/yabloc/yabloc_common/src/cv_decompress.cpp index 5808d5efc61af..0f4bf2b7bc498 100644 --- a/localization/yabloc/yabloc_common/src/cv_decompress.cpp +++ b/localization/yabloc/yabloc_common/src/cv_decompress.cpp @@ -17,6 +17,8 @@ #include #include +#include + #if __has_include() #include // for ROS 2 Jazzy or newer #else diff --git a/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp b/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp index d96285c0d5c00..83edeb4bd9b96 100644 --- a/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp +++ b/localization/yabloc/yabloc_common/src/ground_server/ground_server_core.cpp @@ -28,7 +28,12 @@ #include #include +#include #include +#include +#include +#include +#include namespace yabloc::ground_server { diff --git a/localization/yabloc/yabloc_common/src/ground_server/polygon_operation.cpp b/localization/yabloc/yabloc_common/src/ground_server/polygon_operation.cpp index 11279f6268092..5a8dadec898d6 100644 --- a/localization/yabloc/yabloc_common/src/ground_server/polygon_operation.cpp +++ b/localization/yabloc/yabloc_common/src/ground_server/polygon_operation.cpp @@ -16,6 +16,8 @@ #include +#include + namespace yabloc::ground_server { // cppcheck-suppress unusedFunction diff --git a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp b/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp index 6c3d43f33440f..cbb6f48450b91 100644 --- a/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp +++ b/localization/yabloc/yabloc_common/src/ll2_decomposer/ll2_decomposer_core.cpp @@ -22,6 +22,10 @@ #include +#include +#include +#include + namespace yabloc::ll2_decomposer { Ll2Decomposer::Ll2Decomposer(const rclcpp::NodeOptions & options) : Node("ll2_to_image", options) diff --git a/localization/yabloc/yabloc_common/src/static_tf_subscriber.cpp b/localization/yabloc/yabloc_common/src/static_tf_subscriber.cpp index 3aeaefad12629..afe9d9d70349b 100644 --- a/localization/yabloc/yabloc_common/src/static_tf_subscriber.cpp +++ b/localization/yabloc/yabloc_common/src/static_tf_subscriber.cpp @@ -14,6 +14,9 @@ #include "yabloc_common/static_tf_subscriber.hpp" +#include +#include + namespace yabloc::common { StaticTfSubscriber::StaticTfSubscriber(rclcpp::Clock::SharedPtr clock) diff --git a/localization/yabloc/yabloc_image_processing/src/graph_segment/graph_segment_core.cpp b/localization/yabloc/yabloc_image_processing/src/graph_segment/graph_segment_core.cpp index 9539e44f61276..cedfb570fe74c 100644 --- a/localization/yabloc/yabloc_image_processing/src/graph_segment/graph_segment_core.cpp +++ b/localization/yabloc/yabloc_image_processing/src/graph_segment/graph_segment_core.cpp @@ -21,6 +21,11 @@ #include #include +#include +#include +#include +#include + namespace yabloc::graph_segment { GraphSegment::GraphSegment(const rclcpp::NodeOptions & options) diff --git a/localization/yabloc/yabloc_image_processing/src/graph_segment/similar_area_searcher.cpp b/localization/yabloc/yabloc_image_processing/src/graph_segment/similar_area_searcher.cpp index c7bf41bff459b..5483f4a1e6ae8 100644 --- a/localization/yabloc/yabloc_image_processing/src/graph_segment/similar_area_searcher.cpp +++ b/localization/yabloc/yabloc_image_processing/src/graph_segment/similar_area_searcher.cpp @@ -19,6 +19,9 @@ #include #include +#include +#include +#include namespace yabloc::graph_segment { diff --git a/localization/yabloc/yabloc_image_processing/src/lanelet2_overlay/lanelet2_overlay_core.cpp b/localization/yabloc/yabloc_image_processing/src/lanelet2_overlay/lanelet2_overlay_core.cpp index d31b19406e320..948f5764e2fe3 100644 --- a/localization/yabloc/yabloc_image_processing/src/lanelet2_overlay/lanelet2_overlay_core.cpp +++ b/localization/yabloc/yabloc_image_processing/src/lanelet2_overlay/lanelet2_overlay_core.cpp @@ -26,6 +26,9 @@ #include +#include +#include + namespace yabloc::lanelet2_overlay { Lanelet2Overlay::Lanelet2Overlay(const rclcpp::NodeOptions & options) diff --git a/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp b/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp index c5cec31e24844..8b4dd71561276 100644 --- a/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp +++ b/localization/yabloc/yabloc_image_processing/src/line_segment_detector/line_segment_detector_core.cpp @@ -21,6 +21,8 @@ #include +#include + namespace yabloc::line_segment_detector { LineSegmentDetector::LineSegmentDetector(const rclcpp::NodeOptions & options) diff --git a/localization/yabloc/yabloc_image_processing/src/segment_filter/segment_filter_core.cpp b/localization/yabloc/yabloc_image_processing/src/segment_filter/segment_filter_core.cpp index b844fb69285b5..ab2c241001df7 100644 --- a/localization/yabloc/yabloc_image_processing/src/segment_filter/segment_filter_core.cpp +++ b/localization/yabloc/yabloc_image_processing/src/segment_filter/segment_filter_core.cpp @@ -21,6 +21,11 @@ #include +#include +#include +#include +#include + namespace yabloc::segment_filter { SegmentFilter::SegmentFilter(const rclcpp::NodeOptions & options) diff --git a/localization/yabloc/yabloc_image_processing/src/undistort/undistort_node.cpp b/localization/yabloc/yabloc_image_processing/src/undistort/undistort_node.cpp index 4c33377c8ed0f..98484d5875e14 100644 --- a/localization/yabloc/yabloc_image_processing/src/undistort/undistort_node.cpp +++ b/localization/yabloc/yabloc_image_processing/src/undistort/undistort_node.cpp @@ -24,6 +24,8 @@ #include #include +#include + #if __has_include() #include // for ROS 2 Jazzy or newer #else diff --git a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/hierarchical_cost_map.hpp b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/hierarchical_cost_map.hpp index d6cc4553e29bc..b130ef2db1425 100644 --- a/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/hierarchical_cost_map.hpp +++ b/localization/yabloc/yabloc_particle_filter/include/yabloc_particle_filter/ll2_cost_map/hierarchical_cost_map.hpp @@ -29,6 +29,7 @@ #include #include +#include #include #include #include diff --git a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp index d6a38e7b97b96..4e8decf1308bf 100644 --- a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/camera_particle_corrector_core.cpp @@ -25,7 +25,10 @@ #include +#include #include +#include +#include namespace yabloc::modularized_particle_filter { diff --git a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/filter_line_segments.cpp b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/filter_line_segments.cpp index 105f72920a6de..20c825848b728 100644 --- a/localization/yabloc/yabloc_particle_filter/src/camera_corrector/filter_line_segments.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/camera_corrector/filter_line_segments.cpp @@ -20,6 +20,8 @@ #include #include +#include + namespace yabloc::modularized_particle_filter { cv::Point2f cv2pt(const Eigen::Vector3f & v) diff --git a/localization/yabloc/yabloc_particle_filter/src/common/mean.cpp b/localization/yabloc/yabloc_particle_filter/src/common/mean.cpp index 1a0ef05508c76..0219165734967 100644 --- a/localization/yabloc/yabloc_particle_filter/src/common/mean.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/common/mean.cpp @@ -27,6 +27,7 @@ #include #include #include +#include namespace yabloc::modularized_particle_filter { diff --git a/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp b/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp index 48f2041595a77..fa08deb0da9de 100644 --- a/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp @@ -20,6 +20,8 @@ #include #include +#include + namespace yabloc::modularized_particle_filter { class ParticleVisualize : public rclcpp::Node diff --git a/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp b/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp index 17b22757b4bc5..e9b85f380cf8c 100644 --- a/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/common/visualize.cpp @@ -16,6 +16,8 @@ #include +#include + namespace yabloc::modularized_particle_filter { ParticleVisualizer::ParticleVisualizer(rclcpp::Node & node) diff --git a/localization/yabloc/yabloc_particle_filter/src/correction/abstract_corrector.cpp b/localization/yabloc/yabloc_particle_filter/src/correction/abstract_corrector.cpp index 1c8e2f5976a1d..3c776743824ca 100644 --- a/localization/yabloc/yabloc_particle_filter/src/correction/abstract_corrector.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/correction/abstract_corrector.cpp @@ -14,6 +14,10 @@ #include "yabloc_particle_filter/correction/abstract_corrector.hpp" +#include +#include +#include + namespace yabloc::modularized_particle_filter { AbstractCorrector::AbstractCorrector( diff --git a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/direct_cost_map.cpp b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/direct_cost_map.cpp index c6359a8c8f5fc..4006e8f6fd2c2 100644 --- a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/direct_cost_map.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/direct_cost_map.cpp @@ -14,6 +14,9 @@ #include "yabloc_particle_filter/ll2_cost_map/direct_cost_map.hpp" +#include +#include + namespace yabloc { cv::Mat direct_cost_map(const cv::Mat & cost_map, const cv::Mat & intensity) diff --git a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp index 4f03e3d26ecb6..7450635b70303 100644 --- a/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/ll2_cost_map/hierarchical_cost_map.cpp @@ -22,6 +22,8 @@ #include +#include + namespace yabloc { float Area::unit_length = -1; diff --git a/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp b/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp index 701a2b8763fa3..e92de610e4dec 100644 --- a/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/prediction/predictor.cpp @@ -26,7 +26,9 @@ #include +#include #include +#include namespace yabloc::modularized_particle_filter { diff --git a/localization/yabloc/yabloc_particle_filter/src/prediction/resampler.cpp b/localization/yabloc/yabloc_particle_filter/src/prediction/resampler.cpp index c8c3971ba85b2..f70b4721798be 100644 --- a/localization/yabloc/yabloc_particle_filter/src/prediction/resampler.cpp +++ b/localization/yabloc/yabloc_particle_filter/src/prediction/resampler.cpp @@ -21,6 +21,7 @@ #include #include #include +#include namespace yabloc::modularized_particle_filter { diff --git a/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp index 23f711d1ba17b..0d446e976c089 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/camera_pose_initializer_core.cpp @@ -20,6 +20,10 @@ #include #include +#include +#include +#include + #if __has_include() #include // for ROS 2 Jazzy or newer #else diff --git a/localization/yabloc/yabloc_pose_initializer/src/camera/lane_image.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/lane_image.cpp index d6949c43dbfc5..ca4ca60179bd0 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/lane_image.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/lane_image.cpp @@ -23,6 +23,9 @@ #include #include +#include +#include + namespace yabloc { namespace bg = boost::geometry; diff --git a/localization/yabloc/yabloc_pose_initializer/src/camera/marker_module.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/marker_module.cpp index 0d4dd8bb373e5..9b479c18db07e 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/marker_module.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/marker_module.cpp @@ -16,6 +16,9 @@ #include +#include +#include + namespace yabloc::initializer { diff --git a/localization/yabloc/yabloc_pose_initializer/src/camera/projector_module.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/projector_module.cpp index 449812eff6e09..59226dc0e9171 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/projector_module.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/projector_module.cpp @@ -18,6 +18,8 @@ #include #include +#include + namespace yabloc::initializer { ProjectorModule::ProjectorModule(rclcpp::Node * node) diff --git a/localization/yabloc/yabloc_pose_initializer/src/camera/semantic_segmentation.cpp b/localization/yabloc/yabloc_pose_initializer/src/camera/semantic_segmentation.cpp index 917015269d3e2..472d45749d611 100644 --- a/localization/yabloc/yabloc_pose_initializer/src/camera/semantic_segmentation.cpp +++ b/localization/yabloc/yabloc_pose_initializer/src/camera/semantic_segmentation.cpp @@ -20,6 +20,8 @@ #include #include +#include +#include #include struct SemanticSegmentation::Impl From e9659599f8975132a4a6c92ed5d73d538b0bee0c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:13:58 +0300 Subject: [PATCH 224/273] fix(cpplint): include what you use - map (#9568) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- map/autoware_map_height_fitter/src/map_height_fitter.cpp | 2 ++ .../src/lanelet2_map_loader/lanelet2_map_loader_node.cpp | 1 + .../pointcloud_map_loader/differential_map_loader_module.cpp | 3 +++ .../src/pointcloud_map_loader/partial_map_loader_module.cpp | 2 ++ .../src/pointcloud_map_loader/pointcloud_map_loader_node.cpp | 2 ++ .../src/pointcloud_map_loader/selected_map_loader_module.cpp | 2 ++ map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp | 1 + .../test/test_differential_map_loader_module.cpp | 2 ++ map/autoware_map_loader/test/test_load_pcd_metadata.cpp | 2 ++ .../test/test_partial_map_loader_module.cpp | 2 ++ .../test/test_pointcloud_map_loader_module.cpp | 2 ++ .../test/test_replace_with_absolute_path.cpp | 5 +++++ .../src/map_projection_loader.cpp | 2 ++ .../test/test_load_info_from_lanelet2_map.cpp | 2 ++ .../src/pcd_map_tf_generator_node.cpp | 1 + .../src/vector_map_tf_generator_node.cpp | 1 + map/autoware_map_tf_generator/test/test_uniform_random.cpp | 2 ++ 17 files changed, 34 insertions(+) diff --git a/map/autoware_map_height_fitter/src/map_height_fitter.cpp b/map/autoware_map_height_fitter/src/map_height_fitter.cpp index 732f13e375f05..e86674c86f10d 100644 --- a/map/autoware_map_height_fitter/src/map_height_fitter.cpp +++ b/map/autoware_map_height_fitter/src/map_height_fitter.cpp @@ -29,7 +29,9 @@ #include #include +#include #include +#include namespace autoware::map_height_fitter { diff --git a/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index 0d431e65de3dc..47439508f46ae 100644 --- a/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -49,6 +49,7 @@ #include #include +#include #include #include diff --git a/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp index 160c6f876138d..30a0dd06364d3 100644 --- a/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp @@ -14,7 +14,10 @@ #include "differential_map_loader_module.hpp" +#include +#include #include +#include namespace autoware::map_loader { diff --git a/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp index afa3da7b82b2d..1c96f82b22853 100644 --- a/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp @@ -14,6 +14,8 @@ #include "partial_map_loader_module.hpp" +#include +#include #include namespace autoware::map_loader diff --git a/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp index 2500d96650ae3..a22654faa712a 100644 --- a/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp @@ -20,7 +20,9 @@ #include #include +#include #include +#include #include #include diff --git a/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp index 082d1f545dc14..18b8ace1fec68 100644 --- a/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp @@ -14,6 +14,8 @@ #include "selected_map_loader_module.hpp" +#include +#include #include namespace autoware::map_loader diff --git a/map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp index 172d462947548..cf52986cf58d8 100644 --- a/map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp +++ b/map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp @@ -17,6 +17,7 @@ #include #include +#include #include #include diff --git a/map/autoware_map_loader/test/test_differential_map_loader_module.cpp b/map/autoware_map_loader/test/test_differential_map_loader_module.cpp index cd9b670b32fd3..56be0556bdf04 100644 --- a/map/autoware_map_loader/test/test_differential_map_loader_module.cpp +++ b/map/autoware_map_loader/test/test_differential_map_loader_module.cpp @@ -21,7 +21,9 @@ #include #include +#include #include +#include using autoware::map_loader::DifferentialMapLoaderModule; using autoware_map_msgs::srv::GetDifferentialPointCloudMap; diff --git a/map/autoware_map_loader/test/test_load_pcd_metadata.cpp b/map/autoware_map_loader/test/test_load_pcd_metadata.cpp index dc23c3a9fb2d6..eb246c22afbc3 100644 --- a/map/autoware_map_loader/test/test_load_pcd_metadata.cpp +++ b/map/autoware_map_loader/test/test_load_pcd_metadata.cpp @@ -18,6 +18,8 @@ #include #include +#include +#include using ::testing::ContainerEq; diff --git a/map/autoware_map_loader/test/test_partial_map_loader_module.cpp b/map/autoware_map_loader/test/test_partial_map_loader_module.cpp index fd25b600c81af..85a1f82fb6b2f 100644 --- a/map/autoware_map_loader/test/test_partial_map_loader_module.cpp +++ b/map/autoware_map_loader/test/test_partial_map_loader_module.cpp @@ -20,7 +20,9 @@ #include +#include #include +#include using autoware::map_loader::PartialMapLoaderModule; using autoware_map_msgs::srv::GetPartialPointCloudMap; diff --git a/map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp b/map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp index d61839d5abfc8..3359847a1751c 100644 --- a/map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp +++ b/map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp @@ -25,6 +25,8 @@ #include #include +#include +#include class TestPointcloudMapLoaderModule : public ::testing::Test { diff --git a/map/autoware_map_loader/test/test_replace_with_absolute_path.cpp b/map/autoware_map_loader/test/test_replace_with_absolute_path.cpp index e8ccfbd5fb9f4..00600d51288f6 100644 --- a/map/autoware_map_loader/test/test_replace_with_absolute_path.cpp +++ b/map/autoware_map_loader/test/test_replace_with_absolute_path.cpp @@ -17,6 +17,11 @@ #include #include +#include +#include +#include +#include + using autoware::map_loader::PCDFileMetadata; using autoware::map_loader::replace_with_absolute_path; using ::testing::ContainerEq; diff --git a/map/autoware_map_projection_loader/src/map_projection_loader.cpp b/map/autoware_map_projection_loader/src/map_projection_loader.cpp index a59714e627e83..981380d1d493b 100644 --- a/map/autoware_map_projection_loader/src/map_projection_loader.cpp +++ b/map/autoware_map_projection_loader/src/map_projection_loader.cpp @@ -22,6 +22,8 @@ #include #include +#include +#include namespace autoware::map_projection_loader { diff --git a/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp b/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp index f40084ef819c7..bf2207a777642 100644 --- a/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp +++ b/map/autoware_map_projection_loader/test/test_load_info_from_lanelet2_map.cpp @@ -20,6 +20,8 @@ #include #include +#include +#include void save_dummy_mgrs_lanelet2_map(const std::string & mgrs_coord, const std::string & output_path) { diff --git a/map/autoware_map_tf_generator/src/pcd_map_tf_generator_node.cpp b/map/autoware_map_tf_generator/src/pcd_map_tf_generator_node.cpp index e6edbe99dd210..f1e6b75d2d309 100644 --- a/map/autoware_map_tf_generator/src/pcd_map_tf_generator_node.cpp +++ b/map/autoware_map_tf_generator/src/pcd_map_tf_generator_node.cpp @@ -27,6 +27,7 @@ #include #include #include +#include namespace autoware::map_tf_generator { diff --git a/map/autoware_map_tf_generator/src/vector_map_tf_generator_node.cpp b/map/autoware_map_tf_generator/src/vector_map_tf_generator_node.cpp index e4c397bd04cf1..e31416fb1a2d3 100644 --- a/map/autoware_map_tf_generator/src/vector_map_tf_generator_node.cpp +++ b/map/autoware_map_tf_generator/src/vector_map_tf_generator_node.cpp @@ -24,6 +24,7 @@ #include #include +#include namespace autoware::map_tf_generator { diff --git a/map/autoware_map_tf_generator/test/test_uniform_random.cpp b/map/autoware_map_tf_generator/test/test_uniform_random.cpp index 481f5c6d86859..29557d9327e5a 100644 --- a/map/autoware_map_tf_generator/test/test_uniform_random.cpp +++ b/map/autoware_map_tf_generator/test/test_uniform_random.cpp @@ -16,6 +16,8 @@ #include +#include + using testing::AllOf; using testing::Each; using testing::Ge; From d743658b8bcd243dc47d53d2179801e332a985f4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:14:14 +0300 Subject: [PATCH 225/273] fix(cpplint): include what you use - perception (#9569) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../lib/src/byte_tracker.cpp | 498 +++++------ .../autoware_bytetrack/lib/src/strack.cpp | 4 + .../autoware_bytetrack/lib/src/utils.cpp | 802 +++++++++--------- .../autoware_bytetrack/src/bytetrack.cpp | 2 + .../autoware_bytetrack/src/bytetrack_node.cpp | 2 + .../src/bytetrack_visualizer_node.cpp | 4 + .../test/test_cluster_merger.cpp | 2 + .../node.cpp | 1 + .../node.cpp | 1 + .../voxel_based_compare_map_filter/node.cpp | 1 + .../node.cpp | 1 + .../voxel_grid_map_loader.cpp | 4 + ...test_distance_based_compare_map_filter.cpp | 3 + ...l_based_approximate_compare_map_filter.cpp | 3 + .../test_voxel_based_compare_map_filter.cpp | 3 + ...oxel_distance_based_compare_map_filter.cpp | 3 + .../src/node.cpp | 3 + .../detected_object_feature_remover_node.cpp | 2 + ...t_detected_object_feature_remover_node.cpp | 3 + .../src/lanelet_filter/debug.cpp | 2 + .../src/lanelet_filter/lanelet_filter.cpp | 4 + .../obstacle_pointcloud_validator.cpp | 3 + .../src/position_filter/position_filter.cpp | 2 + .../test_object_position_filter.cpp | 2 + .../lib/euclidean_cluster.cpp | 2 + .../autoware_euclidean_cluster/lib/utils.cpp | 2 + .../voxel_grid_based_euclidean_cluster.cpp | 1 + .../src/euclidean_cluster_node.cpp | 1 + ...oxel_grid_based_euclidean_cluster_node.cpp | 1 + ...est_voxel_grid_based_euclidean_cluster.cpp | 3 + .../src/ransac_ground_filter/node.cpp | 1 + .../scan_ground_filter/grid_ground_filter.cpp | 3 + .../test/test_ransac_ground_filter.cpp | 5 + .../test/test_ray_ground_filter.cpp | 3 + .../test/test_scan_ground_filter.cpp | 3 + .../src/debugger.cpp | 4 + .../src/fusion_node.cpp | 3 + .../src/pointpainting_fusion/node.cpp | 3 + .../pointpainting_fusion/voxel_generator.cpp | 2 + .../src/roi_cluster_fusion/node.cpp | 6 + .../src/roi_detected_object_fusion/node.cpp | 5 + .../src/roi_pointcloud_fusion/node.cpp | 2 + .../segmentation_pointcloud_fusion/node.cpp | 3 + .../src/utils/geometry.cpp | 2 + .../src/utils/utils.cpp | 4 + .../test/test_geometry.cpp | 2 + .../test/test_utils.cpp | 2 + .../src/detector.cpp | 3 + .../src/feature_generator.cpp | 1 + .../src/node.cpp | 2 + .../lib/detection_class_remapper.cpp | 3 + .../lib/network/network_trt.cpp | 3 + .../postprocess/non_maximum_suppression.cpp | 2 + .../lib/preprocess/voxel_generator.cpp | 1 + .../lib/ros_utils.cpp | 3 + .../test/test_detection_class_remapper.cpp | 2 + .../test/test_nms.cpp | 2 + .../test/test_ros_utils.cpp | 3 + .../test/test_voxel_generator.cpp | 3 + .../lib/detection_class_remapper.cpp | 3 + .../lib/network/network_trt.cpp | 2 + .../postprocess/non_maximum_suppression.cpp | 2 + .../lib/preprocess/voxel_generator.cpp | 3 + .../lib/ros_utils.cpp | 3 + .../lib/transfusion_trt.cpp | 1 + .../src/lidar_transfusion_node.cpp | 5 + .../test/test_detection_class_remapper.cpp | 2 + .../test/test_nms.cpp | 2 + .../test/test_postprocess_kernel.cpp | 1 + .../test/test_preprocess_kernel.cpp | 1 + .../test/test_ros_utils.cpp | 3 + .../test/test_voxel_generator.cpp | 3 + .../src/map_based_prediction_node.cpp | 5 + .../src/path_generator.cpp | 3 + .../src/predictor_vru.cpp | 9 + .../src/utils.cpp | 9 + .../lib/tracker/model/tracker_base.cpp | 1 + .../motion_model/bicycle_motion_model.cpp | 2 + .../lib/uncertainty/uncertainty_processor.cpp | 2 + .../src/debugger/debug_object.cpp | 3 + .../src/debugger/debugger.cpp | 3 + .../src/multi_object_tracker_node.cpp | 1 + .../src/processor/input_manager.cpp | 2 + .../src/processor/processor.cpp | 4 + .../src/object_association_merger_node.cpp | 4 + ...radar_crossing_objects_filter_is_noise.cpp | 2 + .../src/association/data_association.cpp | 1 + .../constant_turn_rate_motion_tracker.cpp | 3 + .../tracker/model/linear_motion_tracker.cpp | 3 + .../src/tracker/model/tracker_base.cpp | 1 + .../src/utils/radar_object_tracker_utils.cpp | 4 + .../src/utils/utils.cpp | 2 + .../src/low_intensity_cluster_filter_node.cpp | 2 + .../test_low_intensity_cluster_filter.cpp | 3 + .../lib/tensorrt_shape_estimator.cpp | 5 + .../test/test_shape_estimation_node.cpp | 3 + .../tensorrt_classifier/calibrator.hpp | 2 + .../src/tensorrt_classifier.cpp | 2 + .../autoware/tensorrt_common/logger.hpp | 1 + .../tensorrt_common/tensorrt_common.hpp | 2 + .../src/simple_profiler.cpp | 3 + .../src/tensorrt_common.cpp | 1 + .../autoware/tensorrt_yolox/calibrator.hpp | 2 + .../src/tensorrt_yolox.cpp | 1 + .../src/yolox_single_image_inference_node.cpp | 2 + .../src/decorative_tracker_merger_node.cpp | 3 + .../src/utils/tracker_state.cpp | 5 + .../src/utils/utils.cpp | 1 + .../src/signal_match_validator.cpp | 6 + .../test/test_node.cpp | 4 + .../src/traffic_light_fine_detector_node.cpp | 2 + .../traffic_light_map_based_detector_node.cpp | 5 + ...traffic_light_multi_camera_fusion_node.cpp | 1 + .../src/occlusion_predictor.cpp | 2 + .../shape_draw.cpp | 1 + .../src/run_length_encoder.cpp | 2 + .../perception_utils/test/test_utils.cpp | 2 + 117 files changed, 957 insertions(+), 647 deletions(-) diff --git a/perception/autoware_bytetrack/lib/src/byte_tracker.cpp b/perception/autoware_bytetrack/lib/src/byte_tracker.cpp index a3477e78ad6dd..1d1288cbb2a48 100644 --- a/perception/autoware_bytetrack/lib/src/byte_tracker.cpp +++ b/perception/autoware_bytetrack/lib/src/byte_tracker.cpp @@ -1,248 +1,250 @@ -/* - * MIT License - * - * Copyright (c) 2021 Yifu Zhang - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all - * copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - */ - -// Copyright 2023 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 "byte_tracker.h" - -#include -#include - -ByteTracker::ByteTracker( - int track_buffer, float track_thresh, float high_thresh, float match_thresh) -: track_thresh(track_thresh), high_thresh(high_thresh), match_thresh(match_thresh) - -{ - frame_id = 0; - max_time_lost = track_buffer; - std::cout << "Init ByteTrack!" << std::endl; -} - -ByteTracker::~ByteTracker() -{ -} - -std::vector ByteTracker::update(const std::vector & objects) -{ - ////////////////// Step 1: Get detections ////////////////// - this->frame_id++; - std::vector activated_stracks; - std::vector refind_stracks; - std::vector removed_stracks; - std::vector lost_stracks; - std::vector detections; - std::vector detections_low; - - std::vector detections_cp; - std::vector tracked_stracks_swap; - std::vector resa, resb; - std::vector output_stracks; - - std::vector unconfirmed; - std::vector tracked_stracks; - std::vector strack_pool; - std::vector r_tracked_stracks; - - if (objects.size() > 0) { - for (size_t i = 0; i < objects.size(); i++) { - std::vector tlbr_; - tlbr_.resize(4); - tlbr_[0] = objects[i].rect.x; - tlbr_[1] = objects[i].rect.y; - tlbr_[2] = objects[i].rect.x + objects[i].rect.width; - tlbr_[3] = objects[i].rect.y + objects[i].rect.height; - - float score = objects[i].prob; - - STrack strack(STrack::tlbr_to_tlwh(tlbr_), score, objects[i].label); - if (score >= track_thresh) { - detections.push_back(strack); - } else { - detections_low.push_back(strack); - } - } - } - - // Add newly detected tracklets to tracked_stracks - for (size_t i = 0; i < this->tracked_stracks.size(); i++) { - if (!this->tracked_stracks[i].is_activated) - unconfirmed.push_back(&this->tracked_stracks[i]); - else - tracked_stracks.push_back(&this->tracked_stracks[i]); - } - - ////////////////// Step 2: First association, with IoU ////////////////// - strack_pool = joint_stracks(tracked_stracks, this->lost_stracks); - // do prediction for each stracks - for (size_t i = 0; i < strack_pool.size(); i++) { - strack_pool[i]->predict(this->frame_id); - } - - std::vector > dists; - int dist_size = 0, dist_size_size = 0; - dists = iou_distance(strack_pool, detections, dist_size, dist_size_size); - - std::vector > matches; - std::vector u_track, u_detection; - linear_assignment(dists, dist_size, dist_size_size, match_thresh, matches, u_track, u_detection); - - for (size_t i = 0; i < matches.size(); i++) { - STrack * track = strack_pool[matches[i][0]]; - STrack * det = &detections[matches[i][1]]; - if (track->state == TrackState::Tracked) { - track->update(*det, this->frame_id); - activated_stracks.push_back(*track); - } else { - track->re_activate(*det, this->frame_id, false); - refind_stracks.push_back(*track); - } - } - - ////////////////// Step 3: Second association, using low score dets ////////////////// - for (size_t i = 0; i < u_detection.size(); i++) { - detections_cp.push_back(detections[u_detection[i]]); - } - detections.clear(); - detections.assign(detections_low.begin(), detections_low.end()); - - for (size_t i = 0; i < u_track.size(); i++) { - if (strack_pool[u_track[i]]->state == TrackState::Tracked) { - r_tracked_stracks.push_back(strack_pool[u_track[i]]); - } - } - - dists.clear(); - dists = iou_distance(r_tracked_stracks, detections, dist_size, dist_size_size); - - matches.clear(); - u_track.clear(); - u_detection.clear(); - linear_assignment(dists, dist_size, dist_size_size, 0.5, matches, u_track, u_detection); - - for (size_t i = 0; i < matches.size(); i++) { - STrack * track = r_tracked_stracks[matches[i][0]]; - STrack * det = &detections[matches[i][1]]; - if (track->state == TrackState::Tracked) { - track->update(*det, this->frame_id); - activated_stracks.push_back(*track); - } else { - track->re_activate(*det, this->frame_id, false); - refind_stracks.push_back(*track); - } - } - - for (size_t i = 0; i < u_track.size(); i++) { - STrack * track = r_tracked_stracks[u_track[i]]; - if (track->state != TrackState::Lost) { - track->mark_lost(); - lost_stracks.push_back(*track); - } - } - - // Deal with unconfirmed tracks, usually tracks with only one beginning frame - detections.clear(); - detections.assign(detections_cp.begin(), detections_cp.end()); - - dists.clear(); - dists = iou_distance(unconfirmed, detections, dist_size, dist_size_size); - - matches.clear(); - std::vector u_unconfirmed; - u_detection.clear(); - linear_assignment(dists, dist_size, dist_size_size, 0.7, matches, u_unconfirmed, u_detection); - - for (size_t i = 0; i < matches.size(); i++) { - unconfirmed[matches[i][0]]->update(detections[matches[i][1]], this->frame_id); - activated_stracks.push_back(*unconfirmed[matches[i][0]]); - } - - for (size_t i = 0; i < u_unconfirmed.size(); i++) { - STrack * track = unconfirmed[u_unconfirmed[i]]; - track->mark_removed(); - removed_stracks.push_back(*track); - } - - ////////////////// Step 4: Init new stracks ////////////////// - for (size_t i = 0; i < u_detection.size(); i++) { - STrack * track = &detections[u_detection[i]]; - if (track->score < this->high_thresh) continue; - track->activate(this->frame_id); - activated_stracks.push_back(*track); - } - - ////////////////// Step 5: Update state ////////////////// - for (size_t i = 0; i < this->lost_stracks.size(); i++) { - if (this->frame_id - this->lost_stracks[i].end_frame() > this->max_time_lost) { - this->lost_stracks[i].mark_removed(); - removed_stracks.push_back(this->lost_stracks[i]); - } - } - - for (size_t i = 0; i < this->tracked_stracks.size(); i++) { - if (this->tracked_stracks[i].state == TrackState::Tracked) { - tracked_stracks_swap.push_back(this->tracked_stracks[i]); - } - } - this->tracked_stracks.clear(); - this->tracked_stracks.assign(tracked_stracks_swap.begin(), tracked_stracks_swap.end()); - - this->tracked_stracks = joint_stracks(this->tracked_stracks, activated_stracks); - this->tracked_stracks = joint_stracks(this->tracked_stracks, refind_stracks); - - this->lost_stracks = sub_stracks(this->lost_stracks, this->tracked_stracks); - for (size_t i = 0; i < lost_stracks.size(); i++) { - this->lost_stracks.push_back(lost_stracks[i]); - } - - this->lost_stracks = sub_stracks(this->lost_stracks, this->removed_stracks); - for (size_t i = 0; i < removed_stracks.size(); i++) { - this->removed_stracks.push_back(removed_stracks[i]); - } - - remove_duplicate_stracks(resa, resb, this->tracked_stracks, this->lost_stracks); - - this->tracked_stracks.clear(); - this->tracked_stracks.assign(resa.begin(), resa.end()); - this->lost_stracks.clear(); - this->lost_stracks.assign(resb.begin(), resb.end()); - - for (size_t i = 0; i < this->tracked_stracks.size(); i++) { - if (this->tracked_stracks[i].is_activated) { - output_stracks.push_back(this->tracked_stracks[i]); - } - } - return output_stracks; -} +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// Copyright 2023 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 "byte_tracker.h" + +#include +#include +#include +#include + +ByteTracker::ByteTracker( + int track_buffer, float track_thresh, float high_thresh, float match_thresh) +: track_thresh(track_thresh), high_thresh(high_thresh), match_thresh(match_thresh) + +{ + frame_id = 0; + max_time_lost = track_buffer; + std::cout << "Init ByteTrack!" << std::endl; +} + +ByteTracker::~ByteTracker() +{ +} + +std::vector ByteTracker::update(const std::vector & objects) +{ + ////////////////// Step 1: Get detections ////////////////// + this->frame_id++; + std::vector activated_stracks; + std::vector refind_stracks; + std::vector removed_stracks; + std::vector lost_stracks; + std::vector detections; + std::vector detections_low; + + std::vector detections_cp; + std::vector tracked_stracks_swap; + std::vector resa, resb; + std::vector output_stracks; + + std::vector unconfirmed; + std::vector tracked_stracks; + std::vector strack_pool; + std::vector r_tracked_stracks; + + if (objects.size() > 0) { + for (size_t i = 0; i < objects.size(); i++) { + std::vector tlbr_; + tlbr_.resize(4); + tlbr_[0] = objects[i].rect.x; + tlbr_[1] = objects[i].rect.y; + tlbr_[2] = objects[i].rect.x + objects[i].rect.width; + tlbr_[3] = objects[i].rect.y + objects[i].rect.height; + + float score = objects[i].prob; + + STrack strack(STrack::tlbr_to_tlwh(tlbr_), score, objects[i].label); + if (score >= track_thresh) { + detections.push_back(strack); + } else { + detections_low.push_back(strack); + } + } + } + + // Add newly detected tracklets to tracked_stracks + for (size_t i = 0; i < this->tracked_stracks.size(); i++) { + if (!this->tracked_stracks[i].is_activated) + unconfirmed.push_back(&this->tracked_stracks[i]); + else + tracked_stracks.push_back(&this->tracked_stracks[i]); + } + + ////////////////// Step 2: First association, with IoU ////////////////// + strack_pool = joint_stracks(tracked_stracks, this->lost_stracks); + // do prediction for each stracks + for (size_t i = 0; i < strack_pool.size(); i++) { + strack_pool[i]->predict(this->frame_id); + } + + std::vector > dists; + int dist_size = 0, dist_size_size = 0; + dists = iou_distance(strack_pool, detections, dist_size, dist_size_size); + + std::vector > matches; + std::vector u_track, u_detection; + linear_assignment(dists, dist_size, dist_size_size, match_thresh, matches, u_track, u_detection); + + for (size_t i = 0; i < matches.size(); i++) { + STrack * track = strack_pool[matches[i][0]]; + STrack * det = &detections[matches[i][1]]; + if (track->state == TrackState::Tracked) { + track->update(*det, this->frame_id); + activated_stracks.push_back(*track); + } else { + track->re_activate(*det, this->frame_id, false); + refind_stracks.push_back(*track); + } + } + + ////////////////// Step 3: Second association, using low score dets ////////////////// + for (size_t i = 0; i < u_detection.size(); i++) { + detections_cp.push_back(detections[u_detection[i]]); + } + detections.clear(); + detections.assign(detections_low.begin(), detections_low.end()); + + for (size_t i = 0; i < u_track.size(); i++) { + if (strack_pool[u_track[i]]->state == TrackState::Tracked) { + r_tracked_stracks.push_back(strack_pool[u_track[i]]); + } + } + + dists.clear(); + dists = iou_distance(r_tracked_stracks, detections, dist_size, dist_size_size); + + matches.clear(); + u_track.clear(); + u_detection.clear(); + linear_assignment(dists, dist_size, dist_size_size, 0.5, matches, u_track, u_detection); + + for (size_t i = 0; i < matches.size(); i++) { + STrack * track = r_tracked_stracks[matches[i][0]]; + STrack * det = &detections[matches[i][1]]; + if (track->state == TrackState::Tracked) { + track->update(*det, this->frame_id); + activated_stracks.push_back(*track); + } else { + track->re_activate(*det, this->frame_id, false); + refind_stracks.push_back(*track); + } + } + + for (size_t i = 0; i < u_track.size(); i++) { + STrack * track = r_tracked_stracks[u_track[i]]; + if (track->state != TrackState::Lost) { + track->mark_lost(); + lost_stracks.push_back(*track); + } + } + + // Deal with unconfirmed tracks, usually tracks with only one beginning frame + detections.clear(); + detections.assign(detections_cp.begin(), detections_cp.end()); + + dists.clear(); + dists = iou_distance(unconfirmed, detections, dist_size, dist_size_size); + + matches.clear(); + std::vector u_unconfirmed; + u_detection.clear(); + linear_assignment(dists, dist_size, dist_size_size, 0.7, matches, u_unconfirmed, u_detection); + + for (size_t i = 0; i < matches.size(); i++) { + unconfirmed[matches[i][0]]->update(detections[matches[i][1]], this->frame_id); + activated_stracks.push_back(*unconfirmed[matches[i][0]]); + } + + for (size_t i = 0; i < u_unconfirmed.size(); i++) { + STrack * track = unconfirmed[u_unconfirmed[i]]; + track->mark_removed(); + removed_stracks.push_back(*track); + } + + ////////////////// Step 4: Init new stracks ////////////////// + for (size_t i = 0; i < u_detection.size(); i++) { + STrack * track = &detections[u_detection[i]]; + if (track->score < this->high_thresh) continue; + track->activate(this->frame_id); + activated_stracks.push_back(*track); + } + + ////////////////// Step 5: Update state ////////////////// + for (size_t i = 0; i < this->lost_stracks.size(); i++) { + if (this->frame_id - this->lost_stracks[i].end_frame() > this->max_time_lost) { + this->lost_stracks[i].mark_removed(); + removed_stracks.push_back(this->lost_stracks[i]); + } + } + + for (size_t i = 0; i < this->tracked_stracks.size(); i++) { + if (this->tracked_stracks[i].state == TrackState::Tracked) { + tracked_stracks_swap.push_back(this->tracked_stracks[i]); + } + } + this->tracked_stracks.clear(); + this->tracked_stracks.assign(tracked_stracks_swap.begin(), tracked_stracks_swap.end()); + + this->tracked_stracks = joint_stracks(this->tracked_stracks, activated_stracks); + this->tracked_stracks = joint_stracks(this->tracked_stracks, refind_stracks); + + this->lost_stracks = sub_stracks(this->lost_stracks, this->tracked_stracks); + for (size_t i = 0; i < lost_stracks.size(); i++) { + this->lost_stracks.push_back(lost_stracks[i]); + } + + this->lost_stracks = sub_stracks(this->lost_stracks, this->removed_stracks); + for (size_t i = 0; i < removed_stracks.size(); i++) { + this->removed_stracks.push_back(removed_stracks[i]); + } + + remove_duplicate_stracks(resa, resb, this->tracked_stracks, this->lost_stracks); + + this->tracked_stracks.clear(); + this->tracked_stracks.assign(resa.begin(), resa.end()); + this->lost_stracks.clear(); + this->lost_stracks.assign(resb.begin(), resb.end()); + + for (size_t i = 0; i < this->tracked_stracks.size(); i++) { + if (this->tracked_stracks[i].is_activated) { + output_stracks.push_back(this->tracked_stracks[i]); + } + } + return output_stracks; +} diff --git a/perception/autoware_bytetrack/lib/src/strack.cpp b/perception/autoware_bytetrack/lib/src/strack.cpp index 4f1e03a4c1d4a..14e2ada387d90 100644 --- a/perception/autoware_bytetrack/lib/src/strack.cpp +++ b/perception/autoware_bytetrack/lib/src/strack.cpp @@ -44,6 +44,10 @@ #include +#include +#include +#include + // init static variable bool STrack::_parameters_loaded = false; STrack::KfParams STrack::_kf_parameters; diff --git a/perception/autoware_bytetrack/lib/src/utils.cpp b/perception/autoware_bytetrack/lib/src/utils.cpp index d9ff5af52f6bf..3290b46842bf5 100644 --- a/perception/autoware_bytetrack/lib/src/utils.cpp +++ b/perception/autoware_bytetrack/lib/src/utils.cpp @@ -1,399 +1,403 @@ -/* - * MIT License - * - * Copyright (c) 2021 Yifu Zhang - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in all - * copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - */ - -// Copyright 2023 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 "byte_tracker.h" -#include "lapjv.h" - -#include -#include - -std::vector ByteTracker::joint_stracks( - std::vector & tlista, std::vector & tlistb) -{ - std::map exists; - std::vector res; - for (size_t i = 0; i < tlista.size(); i++) { - exists.insert(std::pair(tlista[i]->track_id, 1)); - res.push_back(tlista[i]); - } - for (size_t i = 0; i < tlistb.size(); i++) { - int tid = tlistb[i].track_id; - if (!exists[tid] || exists.count(tid) == 0) { - exists[tid] = 1; - res.push_back(&tlistb[i]); - } - } - return res; -} - -std::vector ByteTracker::joint_stracks( - std::vector & tlista, std::vector & tlistb) -{ - std::map exists; - std::vector res; - for (size_t i = 0; i < tlista.size(); i++) { - exists.insert(std::pair(tlista[i].track_id, 1)); - res.push_back(tlista[i]); - } - for (size_t i = 0; i < tlistb.size(); i++) { - int tid = tlistb[i].track_id; - if (!exists[tid] || exists.count(tid) == 0) { - exists[tid] = 1; - res.push_back(tlistb[i]); - } - } - return res; -} - -std::vector ByteTracker::sub_stracks( - std::vector & tlista, std::vector & tlistb) -{ - std::map stracks; - for (size_t i = 0; i < tlista.size(); i++) { - stracks.insert(std::pair(tlista[i].track_id, tlista[i])); - } - for (size_t i = 0; i < tlistb.size(); i++) { - int tid = tlistb[i].track_id; - if (stracks.count(tid) != 0) { - stracks.erase(tid); - } - } - - std::vector res; - std::map::iterator it; - for (it = stracks.begin(); it != stracks.end(); ++it) { - res.push_back(it->second); - } - - return res; -} - -void ByteTracker::remove_duplicate_stracks( - std::vector & resa, std::vector & resb, std::vector & stracksa, - std::vector & stracksb) -{ - std::vector> pdist = iou_distance(stracksa, stracksb); - std::vector> pairs; - for (size_t i = 0; i < pdist.size(); i++) { - for (size_t j = 0; j < pdist[i].size(); j++) { - if (pdist[i][j] < 0.15) { - pairs.push_back(std::pair(i, j)); - } - } - } - - std::vector dupa, dupb; - for (size_t i = 0; i < pairs.size(); i++) { - int timep = stracksa[pairs[i].first].frame_id - stracksa[pairs[i].first].start_frame; - int timeq = stracksb[pairs[i].second].frame_id - stracksb[pairs[i].second].start_frame; - if (timep > timeq) - dupb.push_back(pairs[i].second); - else - dupa.push_back(pairs[i].first); - } - - for (size_t i = 0; i < stracksa.size(); i++) { - std::vector::iterator iter = find(dupa.begin(), dupa.end(), i); - if (iter == dupa.end()) { - resa.push_back(stracksa[i]); - } - } - - for (size_t i = 0; i < stracksb.size(); i++) { - std::vector::iterator iter = find(dupb.begin(), dupb.end(), i); - if (iter == dupb.end()) { - resb.push_back(stracksb[i]); - } - } -} - -void ByteTracker::linear_assignment( - std::vector> & cost_matrix, int cost_matrix_size, int cost_matrix_size_size, - float thresh, std::vector> & matches, std::vector & unmatched_a, - std::vector & unmatched_b) -{ - if (cost_matrix.size() == 0) { - for (int i = 0; i < cost_matrix_size; i++) { - unmatched_a.push_back(i); - } - for (int i = 0; i < cost_matrix_size_size; i++) { - unmatched_b.push_back(i); - } - return; - } - - std::vector rowsol; - std::vector colsol; - [[maybe_unused]] float c = lapjv(cost_matrix, rowsol, colsol, true, thresh); - for (size_t i = 0; i < rowsol.size(); i++) { - if (rowsol[i] >= 0) { - std::vector match; - match.push_back(i); - match.push_back(rowsol[i]); - matches.push_back(match); - } else { - unmatched_a.push_back(i); - } - } - - for (size_t i = 0; i < colsol.size(); i++) { - if (colsol[i] < 0) { - unmatched_b.push_back(i); - } - } -} - -std::vector> ByteTracker::ious( - std::vector> & atlbrs, std::vector> & btlbrs) -{ - std::vector> ious; - if (atlbrs.size() * btlbrs.size() == 0) return ious; - - ious.resize(atlbrs.size()); - for (size_t i = 0; i < ious.size(); i++) { - ious[i].resize(btlbrs.size()); - } - - // bbox_ious - for (size_t k = 0; k < btlbrs.size(); k++) { - float box_area = (btlbrs[k][2] - btlbrs[k][0] + 1) * (btlbrs[k][3] - btlbrs[k][1] + 1); - for (size_t n = 0; n < atlbrs.size(); n++) { - float iw = std::min(atlbrs[n][2], btlbrs[k][2]) - std::max(atlbrs[n][0], btlbrs[k][0]) + 1; - if (iw > 0) { - float ih = std::min(atlbrs[n][3], btlbrs[k][3]) - std::max(atlbrs[n][1], btlbrs[k][1]) + 1; - if (ih > 0) { - float ua = (atlbrs[n][2] - atlbrs[n][0] + 1) * (atlbrs[n][3] - atlbrs[n][1] + 1) + - box_area - iw * ih; - ious[n][k] = iw * ih / ua; - } else { - ious[n][k] = 0.0; - } - } else { - ious[n][k] = 0.0; - } - } - } - - return ious; -} - -std::vector> ByteTracker::iou_distance( - std::vector & atracks, std::vector & btracks, int & dist_size, - int & dist_size_size) -{ - std::vector> cost_matrix; - if (atracks.size() * btracks.size() == 0) { - dist_size = atracks.size(); - dist_size_size = btracks.size(); - return cost_matrix; - } - std::vector> atlbrs, btlbrs; - for (size_t i = 0; i < atracks.size(); i++) { - atlbrs.push_back(atracks[i]->tlbr); - } - for (size_t i = 0; i < btracks.size(); i++) { - btlbrs.push_back(btracks[i].tlbr); - } - - dist_size = atracks.size(); - dist_size_size = btracks.size(); - - std::vector> _ious = ious(atlbrs, btlbrs); - - for (size_t i = 0; i < _ious.size(); i++) { - std::vector _iou; - for (size_t j = 0; j < _ious[i].size(); j++) { - _iou.push_back(1 - _ious[i][j]); - } - cost_matrix.push_back(_iou); - } - - return cost_matrix; -} - -std::vector> ByteTracker::iou_distance( - std::vector & atracks, std::vector & btracks) -{ - std::vector> atlbrs, btlbrs; - for (size_t i = 0; i < atracks.size(); i++) { - atlbrs.push_back(atracks[i].tlbr); - } - for (size_t i = 0; i < btracks.size(); i++) { - btlbrs.push_back(btracks[i].tlbr); - } - - std::vector> _ious = ious(atlbrs, btlbrs); - std::vector> cost_matrix; - for (size_t i = 0; i < _ious.size(); i++) { - std::vector _iou; - for (size_t j = 0; j < _ious[i].size(); j++) { - _iou.push_back(1 - _ious[i][j]); - } - cost_matrix.push_back(_iou); - } - - return cost_matrix; -} - -double ByteTracker::lapjv( - const std::vector> & cost, std::vector & rowsol, - std::vector & colsol, bool extend_cost, float cost_limit, bool return_cost) -{ - std::vector> cost_c; - cost_c.assign(cost.begin(), cost.end()); - - int n_rows = cost.size(); - int n_cols = cost[0].size(); - rowsol.resize(n_rows); - colsol.resize(n_cols); - - int n = 0; - if (n_rows == n_cols) { - n = n_rows; - } else { - if (!extend_cost) { - std::cout << "set extend_cost=True" << std::endl; - // system("pause"); - exit(0); - } - } - - if (extend_cost || cost_limit < std::numeric_limits::max()) { - std::vector> cost_c_extended; - - n = n_rows + n_cols; - cost_c_extended.resize(n); - for (size_t i = 0; i < cost_c_extended.size(); i++) cost_c_extended[i].resize(n); - - if (cost_limit < std::numeric_limits::max()) { - for (size_t i = 0; i < cost_c_extended.size(); i++) { - for (size_t j = 0; j < cost_c_extended[i].size(); j++) { - cost_c_extended[i][j] = cost_limit / 2.0; - } - } - } else { - float cost_max = -1; - for (size_t i = 0; i < cost_c.size(); i++) { - for (size_t j = 0; j < cost_c[i].size(); j++) { - if (cost_c[i][j] > cost_max) cost_max = cost_c[i][j]; - } - } - for (size_t i = 0; i < cost_c_extended.size(); i++) { - for (size_t j = 0; j < cost_c_extended[i].size(); j++) { - cost_c_extended[i][j] = cost_max + 1; - } - } - } - - for (size_t i = n_rows; i < cost_c_extended.size(); i++) { - for (size_t j = n_cols; j < cost_c_extended[i].size(); j++) { - cost_c_extended[i][j] = 0; - } - } - for (int i = 0; i < n_rows; i++) { - for (int j = 0; j < n_cols; j++) { - cost_c_extended[i][j] = cost_c[i][j]; - } - } - - cost_c.clear(); - cost_c.assign(cost_c_extended.begin(), cost_c_extended.end()); - } - - double ** cost_ptr; - cost_ptr = new double *[sizeof(double *) * n]; - for (int i = 0; i < n; i++) cost_ptr[i] = new double[sizeof(double) * n]; - - for (int i = 0; i < n; i++) { - for (int j = 0; j < n; j++) { - cost_ptr[i][j] = cost_c[i][j]; - } - } - - int * x_c = new int[sizeof(int) * n]; - int * y_c = new int[sizeof(int) * n]; - - int ret = lapjv_internal(n, cost_ptr, x_c, y_c); - if (ret != 0) { - std::cout << "Calculate Wrong!" << std::endl; - // system("pause"); - exit(0); - } - - double opt = 0.0; - - if (n != n_rows) { - for (int i = 0; i < n; i++) { - if (x_c[i] >= n_cols) x_c[i] = -1; - if (y_c[i] >= n_rows) y_c[i] = -1; - } - for (int i = 0; i < n_rows; i++) { - rowsol[i] = x_c[i]; - } - for (int i = 0; i < n_cols; i++) { - colsol[i] = y_c[i]; - } - - if (return_cost) { - for (size_t i = 0; i < rowsol.size(); i++) { - if (rowsol[i] != -1) { - opt += cost_ptr[i][rowsol[i]]; - } - } - } - } else if (return_cost) { - for (size_t i = 0; i < rowsol.size(); i++) { - opt += cost_ptr[i][rowsol[i]]; - } - } - - for (int i = 0; i < n; i++) { - delete[] cost_ptr[i]; - } - delete[] cost_ptr; - delete[] x_c; - delete[] y_c; - - return opt; -} - -cv::Scalar ByteTracker::get_color(int idx) -{ - idx += 3; - return cv::Scalar(37 * idx % 255, 17 * idx % 255, 29 * idx % 255); -} +/* + * MIT License + * + * Copyright (c) 2021 Yifu Zhang + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in all + * copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +// Copyright 2023 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 "byte_tracker.h" +#include "lapjv.h" + +#include +#include +#include +#include +#include +#include + +std::vector ByteTracker::joint_stracks( + std::vector & tlista, std::vector & tlistb) +{ + std::map exists; + std::vector res; + for (size_t i = 0; i < tlista.size(); i++) { + exists.insert(std::pair(tlista[i]->track_id, 1)); + res.push_back(tlista[i]); + } + for (size_t i = 0; i < tlistb.size(); i++) { + int tid = tlistb[i].track_id; + if (!exists[tid] || exists.count(tid) == 0) { + exists[tid] = 1; + res.push_back(&tlistb[i]); + } + } + return res; +} + +std::vector ByteTracker::joint_stracks( + std::vector & tlista, std::vector & tlistb) +{ + std::map exists; + std::vector res; + for (size_t i = 0; i < tlista.size(); i++) { + exists.insert(std::pair(tlista[i].track_id, 1)); + res.push_back(tlista[i]); + } + for (size_t i = 0; i < tlistb.size(); i++) { + int tid = tlistb[i].track_id; + if (!exists[tid] || exists.count(tid) == 0) { + exists[tid] = 1; + res.push_back(tlistb[i]); + } + } + return res; +} + +std::vector ByteTracker::sub_stracks( + std::vector & tlista, std::vector & tlistb) +{ + std::map stracks; + for (size_t i = 0; i < tlista.size(); i++) { + stracks.insert(std::pair(tlista[i].track_id, tlista[i])); + } + for (size_t i = 0; i < tlistb.size(); i++) { + int tid = tlistb[i].track_id; + if (stracks.count(tid) != 0) { + stracks.erase(tid); + } + } + + std::vector res; + std::map::iterator it; + for (it = stracks.begin(); it != stracks.end(); ++it) { + res.push_back(it->second); + } + + return res; +} + +void ByteTracker::remove_duplicate_stracks( + std::vector & resa, std::vector & resb, std::vector & stracksa, + std::vector & stracksb) +{ + std::vector> pdist = iou_distance(stracksa, stracksb); + std::vector> pairs; + for (size_t i = 0; i < pdist.size(); i++) { + for (size_t j = 0; j < pdist[i].size(); j++) { + if (pdist[i][j] < 0.15) { + pairs.push_back(std::pair(i, j)); + } + } + } + + std::vector dupa, dupb; + for (size_t i = 0; i < pairs.size(); i++) { + int timep = stracksa[pairs[i].first].frame_id - stracksa[pairs[i].first].start_frame; + int timeq = stracksb[pairs[i].second].frame_id - stracksb[pairs[i].second].start_frame; + if (timep > timeq) + dupb.push_back(pairs[i].second); + else + dupa.push_back(pairs[i].first); + } + + for (size_t i = 0; i < stracksa.size(); i++) { + std::vector::iterator iter = find(dupa.begin(), dupa.end(), i); + if (iter == dupa.end()) { + resa.push_back(stracksa[i]); + } + } + + for (size_t i = 0; i < stracksb.size(); i++) { + std::vector::iterator iter = find(dupb.begin(), dupb.end(), i); + if (iter == dupb.end()) { + resb.push_back(stracksb[i]); + } + } +} + +void ByteTracker::linear_assignment( + std::vector> & cost_matrix, int cost_matrix_size, int cost_matrix_size_size, + float thresh, std::vector> & matches, std::vector & unmatched_a, + std::vector & unmatched_b) +{ + if (cost_matrix.size() == 0) { + for (int i = 0; i < cost_matrix_size; i++) { + unmatched_a.push_back(i); + } + for (int i = 0; i < cost_matrix_size_size; i++) { + unmatched_b.push_back(i); + } + return; + } + + std::vector rowsol; + std::vector colsol; + [[maybe_unused]] float c = lapjv(cost_matrix, rowsol, colsol, true, thresh); + for (size_t i = 0; i < rowsol.size(); i++) { + if (rowsol[i] >= 0) { + std::vector match; + match.push_back(i); + match.push_back(rowsol[i]); + matches.push_back(match); + } else { + unmatched_a.push_back(i); + } + } + + for (size_t i = 0; i < colsol.size(); i++) { + if (colsol[i] < 0) { + unmatched_b.push_back(i); + } + } +} + +std::vector> ByteTracker::ious( + std::vector> & atlbrs, std::vector> & btlbrs) +{ + std::vector> ious; + if (atlbrs.size() * btlbrs.size() == 0) return ious; + + ious.resize(atlbrs.size()); + for (size_t i = 0; i < ious.size(); i++) { + ious[i].resize(btlbrs.size()); + } + + // bbox_ious + for (size_t k = 0; k < btlbrs.size(); k++) { + float box_area = (btlbrs[k][2] - btlbrs[k][0] + 1) * (btlbrs[k][3] - btlbrs[k][1] + 1); + for (size_t n = 0; n < atlbrs.size(); n++) { + float iw = std::min(atlbrs[n][2], btlbrs[k][2]) - std::max(atlbrs[n][0], btlbrs[k][0]) + 1; + if (iw > 0) { + float ih = std::min(atlbrs[n][3], btlbrs[k][3]) - std::max(atlbrs[n][1], btlbrs[k][1]) + 1; + if (ih > 0) { + float ua = (atlbrs[n][2] - atlbrs[n][0] + 1) * (atlbrs[n][3] - atlbrs[n][1] + 1) + + box_area - iw * ih; + ious[n][k] = iw * ih / ua; + } else { + ious[n][k] = 0.0; + } + } else { + ious[n][k] = 0.0; + } + } + } + + return ious; +} + +std::vector> ByteTracker::iou_distance( + std::vector & atracks, std::vector & btracks, int & dist_size, + int & dist_size_size) +{ + std::vector> cost_matrix; + if (atracks.size() * btracks.size() == 0) { + dist_size = atracks.size(); + dist_size_size = btracks.size(); + return cost_matrix; + } + std::vector> atlbrs, btlbrs; + for (size_t i = 0; i < atracks.size(); i++) { + atlbrs.push_back(atracks[i]->tlbr); + } + for (size_t i = 0; i < btracks.size(); i++) { + btlbrs.push_back(btracks[i].tlbr); + } + + dist_size = atracks.size(); + dist_size_size = btracks.size(); + + std::vector> _ious = ious(atlbrs, btlbrs); + + for (size_t i = 0; i < _ious.size(); i++) { + std::vector _iou; + for (size_t j = 0; j < _ious[i].size(); j++) { + _iou.push_back(1 - _ious[i][j]); + } + cost_matrix.push_back(_iou); + } + + return cost_matrix; +} + +std::vector> ByteTracker::iou_distance( + std::vector & atracks, std::vector & btracks) +{ + std::vector> atlbrs, btlbrs; + for (size_t i = 0; i < atracks.size(); i++) { + atlbrs.push_back(atracks[i].tlbr); + } + for (size_t i = 0; i < btracks.size(); i++) { + btlbrs.push_back(btracks[i].tlbr); + } + + std::vector> _ious = ious(atlbrs, btlbrs); + std::vector> cost_matrix; + for (size_t i = 0; i < _ious.size(); i++) { + std::vector _iou; + for (size_t j = 0; j < _ious[i].size(); j++) { + _iou.push_back(1 - _ious[i][j]); + } + cost_matrix.push_back(_iou); + } + + return cost_matrix; +} + +double ByteTracker::lapjv( + const std::vector> & cost, std::vector & rowsol, + std::vector & colsol, bool extend_cost, float cost_limit, bool return_cost) +{ + std::vector> cost_c; + cost_c.assign(cost.begin(), cost.end()); + + int n_rows = cost.size(); + int n_cols = cost[0].size(); + rowsol.resize(n_rows); + colsol.resize(n_cols); + + int n = 0; + if (n_rows == n_cols) { + n = n_rows; + } else { + if (!extend_cost) { + std::cout << "set extend_cost=True" << std::endl; + // system("pause"); + exit(0); + } + } + + if (extend_cost || cost_limit < std::numeric_limits::max()) { + std::vector> cost_c_extended; + + n = n_rows + n_cols; + cost_c_extended.resize(n); + for (size_t i = 0; i < cost_c_extended.size(); i++) cost_c_extended[i].resize(n); + + if (cost_limit < std::numeric_limits::max()) { + for (size_t i = 0; i < cost_c_extended.size(); i++) { + for (size_t j = 0; j < cost_c_extended[i].size(); j++) { + cost_c_extended[i][j] = cost_limit / 2.0; + } + } + } else { + float cost_max = -1; + for (size_t i = 0; i < cost_c.size(); i++) { + for (size_t j = 0; j < cost_c[i].size(); j++) { + if (cost_c[i][j] > cost_max) cost_max = cost_c[i][j]; + } + } + for (size_t i = 0; i < cost_c_extended.size(); i++) { + for (size_t j = 0; j < cost_c_extended[i].size(); j++) { + cost_c_extended[i][j] = cost_max + 1; + } + } + } + + for (size_t i = n_rows; i < cost_c_extended.size(); i++) { + for (size_t j = n_cols; j < cost_c_extended[i].size(); j++) { + cost_c_extended[i][j] = 0; + } + } + for (int i = 0; i < n_rows; i++) { + for (int j = 0; j < n_cols; j++) { + cost_c_extended[i][j] = cost_c[i][j]; + } + } + + cost_c.clear(); + cost_c.assign(cost_c_extended.begin(), cost_c_extended.end()); + } + + double ** cost_ptr; + cost_ptr = new double *[sizeof(double *) * n]; + for (int i = 0; i < n; i++) cost_ptr[i] = new double[sizeof(double) * n]; + + for (int i = 0; i < n; i++) { + for (int j = 0; j < n; j++) { + cost_ptr[i][j] = cost_c[i][j]; + } + } + + int * x_c = new int[sizeof(int) * n]; + int * y_c = new int[sizeof(int) * n]; + + int ret = lapjv_internal(n, cost_ptr, x_c, y_c); + if (ret != 0) { + std::cout << "Calculate Wrong!" << std::endl; + // system("pause"); + exit(0); + } + + double opt = 0.0; + + if (n != n_rows) { + for (int i = 0; i < n; i++) { + if (x_c[i] >= n_cols) x_c[i] = -1; + if (y_c[i] >= n_rows) y_c[i] = -1; + } + for (int i = 0; i < n_rows; i++) { + rowsol[i] = x_c[i]; + } + for (int i = 0; i < n_cols; i++) { + colsol[i] = y_c[i]; + } + + if (return_cost) { + for (size_t i = 0; i < rowsol.size(); i++) { + if (rowsol[i] != -1) { + opt += cost_ptr[i][rowsol[i]]; + } + } + } + } else if (return_cost) { + for (size_t i = 0; i < rowsol.size(); i++) { + opt += cost_ptr[i][rowsol[i]]; + } + } + + for (int i = 0; i < n; i++) { + delete[] cost_ptr[i]; + } + delete[] cost_ptr; + delete[] x_c; + delete[] y_c; + + return opt; +} + +cv::Scalar ByteTracker::get_color(int idx) +{ + idx += 3; + return cv::Scalar(37 * idx % 255, 17 * idx % 255, 29 * idx % 255); +} diff --git a/perception/autoware_bytetrack/src/bytetrack.cpp b/perception/autoware_bytetrack/src/bytetrack.cpp index 0edeb0ac4e247..af93034972a83 100644 --- a/perception/autoware_bytetrack/src/bytetrack.cpp +++ b/perception/autoware_bytetrack/src/bytetrack.cpp @@ -17,6 +17,8 @@ #include #include #include +#include +#include namespace autoware::bytetrack { diff --git a/perception/autoware_bytetrack/src/bytetrack_node.cpp b/perception/autoware_bytetrack/src/bytetrack_node.cpp index 1da7ebc4055f0..bee93b623ae06 100644 --- a/perception/autoware_bytetrack/src/bytetrack_node.cpp +++ b/perception/autoware_bytetrack/src/bytetrack_node.cpp @@ -20,6 +20,8 @@ #include +#include +#include #include #include diff --git a/perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp b/perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp index 97cee4f67ccb9..a6fc463dd80f1 100644 --- a/perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp +++ b/perception/autoware_bytetrack/src/bytetrack_visualizer_node.cpp @@ -17,6 +17,10 @@ #include #include +#include +#include +#include + #if __has_include() #include #else diff --git a/perception/autoware_cluster_merger/test/test_cluster_merger.cpp b/perception/autoware_cluster_merger/test/test_cluster_merger.cpp index d530832659a2f..640bac0afe5fa 100644 --- a/perception/autoware_cluster_merger/test/test_cluster_merger.cpp +++ b/perception/autoware_cluster_merger/test/test_cluster_merger.cpp @@ -19,6 +19,8 @@ #include +#include +#include #include using autoware::cluster_merger::ClusterMergerNode; diff --git a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp index a2e3afd62cdad..ae07d54ad53d6 100644 --- a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp @@ -21,6 +21,7 @@ #include #include +#include #include namespace autoware::compare_map_segmentation diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp index a02a6865ef9ef..9f325b36676be 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp @@ -21,6 +21,7 @@ #include #include +#include #include namespace autoware::compare_map_segmentation diff --git a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp index cdad52b5a278d..a31d5ec5dd6d6 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp @@ -21,6 +21,7 @@ #include #include +#include #include namespace autoware::compare_map_segmentation diff --git a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp index 291a19d02ed4b..d0bcf381cd62f 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp @@ -21,6 +21,7 @@ #include #include +#include #include namespace autoware::compare_map_segmentation 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 b57874d7d3b24..d55712f5b756e 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 @@ -14,6 +14,10 @@ #include "voxel_grid_map_loader.hpp" +#include +#include +#include + namespace autoware::compare_map_segmentation { VoxelGridMapLoader::VoxelGridMapLoader( diff --git a/perception/autoware_compare_map_segmentation/test/test_distance_based_compare_map_filter.cpp b/perception/autoware_compare_map_segmentation/test/test_distance_based_compare_map_filter.cpp index 2ed66b9875ef8..683ee8f129d95 100644 --- a/perception/autoware_compare_map_segmentation/test/test_distance_based_compare_map_filter.cpp +++ b/perception/autoware_compare_map_segmentation/test/test_distance_based_compare_map_filter.cpp @@ -23,6 +23,9 @@ #include +#include +#include + using autoware::compare_map_segmentation::DistanceBasedCompareMapFilterComponent; using autoware::point_types::PointXYZIRC; using autoware::point_types::PointXYZIRCGenerator; diff --git a/perception/autoware_compare_map_segmentation/test/test_voxel_based_approximate_compare_map_filter.cpp b/perception/autoware_compare_map_segmentation/test/test_voxel_based_approximate_compare_map_filter.cpp index 816ba7e8174c7..055a0a669795b 100644 --- a/perception/autoware_compare_map_segmentation/test/test_voxel_based_approximate_compare_map_filter.cpp +++ b/perception/autoware_compare_map_segmentation/test/test_voxel_based_approximate_compare_map_filter.cpp @@ -23,6 +23,9 @@ #include +#include +#include + using autoware::compare_map_segmentation::VoxelBasedApproximateCompareMapFilterComponent; using autoware::point_types::PointXYZIRC; using autoware::point_types::PointXYZIRCGenerator; diff --git a/perception/autoware_compare_map_segmentation/test/test_voxel_based_compare_map_filter.cpp b/perception/autoware_compare_map_segmentation/test/test_voxel_based_compare_map_filter.cpp index 4fa0ab6321f1c..24b06ef917e65 100644 --- a/perception/autoware_compare_map_segmentation/test/test_voxel_based_compare_map_filter.cpp +++ b/perception/autoware_compare_map_segmentation/test/test_voxel_based_compare_map_filter.cpp @@ -23,6 +23,9 @@ #include +#include +#include + using autoware::compare_map_segmentation::VoxelBasedCompareMapFilterComponent; using autoware::point_types::PointXYZIRC; using autoware::point_types::PointXYZIRCGenerator; diff --git a/perception/autoware_compare_map_segmentation/test/test_voxel_distance_based_compare_map_filter.cpp b/perception/autoware_compare_map_segmentation/test/test_voxel_distance_based_compare_map_filter.cpp index 946eef9bd0a0e..c478eb54e9808 100644 --- a/perception/autoware_compare_map_segmentation/test/test_voxel_distance_based_compare_map_filter.cpp +++ b/perception/autoware_compare_map_segmentation/test/test_voxel_distance_based_compare_map_filter.cpp @@ -23,6 +23,9 @@ #include +#include +#include + using autoware::compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent; using autoware::point_types::PointXYZIRC; using autoware::point_types::PointXYZIRCGenerator; diff --git a/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp b/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp index 5d9f06c3432b5..b0ec4d0e5ffd0 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp +++ b/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp @@ -16,8 +16,11 @@ #include #include +#include #include #include +#include +#include #include #include diff --git a/perception/autoware_detected_object_feature_remover/src/detected_object_feature_remover_node.cpp b/perception/autoware_detected_object_feature_remover/src/detected_object_feature_remover_node.cpp index 47fe67de9d9aa..21e069144203c 100644 --- a/perception/autoware_detected_object_feature_remover/src/detected_object_feature_remover_node.cpp +++ b/perception/autoware_detected_object_feature_remover/src/detected_object_feature_remover_node.cpp @@ -14,6 +14,8 @@ #include "detected_object_feature_remover_node.hpp" +#include + namespace autoware::detected_object_feature_remover { DetectedObjectFeatureRemover::DetectedObjectFeatureRemover(const rclcpp::NodeOptions & node_options) diff --git a/perception/autoware_detected_object_feature_remover/test/test_detected_object_feature_remover_node.cpp b/perception/autoware_detected_object_feature_remover/test/test_detected_object_feature_remover_node.cpp index e54151786278a..c180387ecd63e 100644 --- a/perception/autoware_detected_object_feature_remover/test/test_detected_object_feature_remover_node.cpp +++ b/perception/autoware_detected_object_feature_remover/test/test_detected_object_feature_remover_node.cpp @@ -21,6 +21,9 @@ #include +#include +#include + namespace { using autoware::detected_object_feature_remover::DetectedObjectFeatureRemover; diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp b/perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp index b4116982f5b94..b3765a6a45870 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp @@ -25,6 +25,8 @@ #include #include +#include +#include namespace autoware::detected_object_validation { diff --git a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp index 5e199a9ea9fad..f91c4e2036227 100644 --- a/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp +++ b/perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp @@ -30,6 +30,10 @@ #include #include +#include +#include +#include + namespace autoware::detected_object_validation { namespace lanelet_filter diff --git a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp index 090ca795289fa..194f333acd87e 100644 --- a/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp +++ b/perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp @@ -21,6 +21,9 @@ #include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/perception/autoware_detected_object_validation/src/position_filter/position_filter.cpp b/perception/autoware_detected_object_validation/src/position_filter/position_filter.cpp index 3b88628aa6d84..8c1db64c61d51 100644 --- a/perception/autoware_detected_object_validation/src/position_filter/position_filter.cpp +++ b/perception/autoware_detected_object_validation/src/position_filter/position_filter.cpp @@ -14,6 +14,8 @@ #include "position_filter.hpp" +#include + namespace autoware::detected_object_validation { namespace position_filter diff --git a/perception/autoware_detected_object_validation/test/object_position_filter/test_object_position_filter.cpp b/perception/autoware_detected_object_validation/test/object_position_filter/test_object_position_filter.cpp index 7a6169254348c..651cec7ae236f 100644 --- a/perception/autoware_detected_object_validation/test/object_position_filter/test_object_position_filter.cpp +++ b/perception/autoware_detected_object_validation/test/object_position_filter/test_object_position_filter.cpp @@ -19,6 +19,8 @@ #include +#include +#include #include using autoware::detected_object_validation::position_filter::ObjectPositionFilterNode; diff --git a/perception/autoware_euclidean_cluster/lib/euclidean_cluster.cpp b/perception/autoware_euclidean_cluster/lib/euclidean_cluster.cpp index 0481b7e1b742d..ce56823894bb2 100644 --- a/perception/autoware_euclidean_cluster/lib/euclidean_cluster.cpp +++ b/perception/autoware_euclidean_cluster/lib/euclidean_cluster.cpp @@ -17,6 +17,8 @@ #include #include +#include + namespace autoware::euclidean_cluster { EuclideanCluster::EuclideanCluster() diff --git a/perception/autoware_euclidean_cluster/lib/utils.cpp b/perception/autoware_euclidean_cluster/lib/utils.cpp index 624c838ef0647..6789c71310a7f 100644 --- a/perception/autoware_euclidean_cluster/lib/utils.cpp +++ b/perception/autoware_euclidean_cluster/lib/utils.cpp @@ -19,6 +19,8 @@ #include #include +#include + namespace autoware::euclidean_cluster { geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud) diff --git a/perception/autoware_euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp b/perception/autoware_euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp index f6e8315a02b77..5f4ef98384d23 100644 --- a/perception/autoware_euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp +++ b/perception/autoware_euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp @@ -18,6 +18,7 @@ #include #include +#include namespace autoware::euclidean_cluster { diff --git a/perception/autoware_euclidean_cluster/src/euclidean_cluster_node.cpp b/perception/autoware_euclidean_cluster/src/euclidean_cluster_node.cpp index b0b9448dfc0c4..cccb05160942c 100644 --- a/perception/autoware_euclidean_cluster/src/euclidean_cluster_node.cpp +++ b/perception/autoware_euclidean_cluster/src/euclidean_cluster_node.cpp @@ -16,6 +16,7 @@ #include "autoware/euclidean_cluster/utils.hpp" +#include #include namespace autoware::euclidean_cluster diff --git a/perception/autoware_euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp b/perception/autoware_euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp index e54c55e4873ee..019001c54ba49 100644 --- a/perception/autoware_euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp +++ b/perception/autoware_euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp @@ -16,6 +16,7 @@ #include "autoware/euclidean_cluster/utils.hpp" +#include #include namespace autoware::euclidean_cluster diff --git a/perception/autoware_euclidean_cluster/test/test_voxel_grid_based_euclidean_cluster.cpp b/perception/autoware_euclidean_cluster/test/test_voxel_grid_based_euclidean_cluster.cpp index 759e2b3653868..256cce4841873 100644 --- a/perception/autoware_euclidean_cluster/test/test_voxel_grid_based_euclidean_cluster.cpp +++ b/perception/autoware_euclidean_cluster/test/test_voxel_grid_based_euclidean_cluster.cpp @@ -23,6 +23,9 @@ #include +#include +#include + using autoware::point_types::PointXYZI; void setPointCloud2Fields(sensor_msgs::msg::PointCloud2 & pointcloud) { 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 83e0538bd56de..5ef05485d36a5 100644 --- a/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp +++ b/perception/autoware_ground_segmentation/src/ransac_ground_filter/node.cpp @@ -19,6 +19,7 @@ #include #include +#include #include #include #include diff --git a/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.cpp b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.cpp index 8b754357cd45f..9c8106f59b917 100644 --- a/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.cpp +++ b/perception/autoware_ground_segmentation/src/scan_ground_filter/grid_ground_filter.cpp @@ -18,6 +18,9 @@ #include +#include +#include + namespace autoware::ground_segmentation { diff --git a/perception/autoware_ground_segmentation/test/test_ransac_ground_filter.cpp b/perception/autoware_ground_segmentation/test/test_ransac_ground_filter.cpp index a3f8b9d4b19b3..5e4f16e359607 100644 --- a/perception/autoware_ground_segmentation/test/test_ransac_ground_filter.cpp +++ b/perception/autoware_ground_segmentation/test/test_ransac_ground_filter.cpp @@ -24,6 +24,11 @@ #include +#include +#include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #include diff --git a/perception/autoware_ground_segmentation/test/test_ray_ground_filter.cpp b/perception/autoware_ground_segmentation/test/test_ray_ground_filter.cpp index 1e494f683f181..3626aaa837309 100644 --- a/perception/autoware_ground_segmentation/test/test_ray_ground_filter.cpp +++ b/perception/autoware_ground_segmentation/test/test_ray_ground_filter.cpp @@ -21,6 +21,9 @@ #include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #include diff --git a/perception/autoware_ground_segmentation/test/test_scan_ground_filter.cpp b/perception/autoware_ground_segmentation/test/test_scan_ground_filter.cpp index 706ffff3ce511..2c0f649168703 100644 --- a/perception/autoware_ground_segmentation/test/test_scan_ground_filter.cpp +++ b/perception/autoware_ground_segmentation/test/test_scan_ground_filter.cpp @@ -20,6 +20,9 @@ #include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #include diff --git a/perception/autoware_image_projection_based_fusion/src/debugger.cpp b/perception/autoware_image_projection_based_fusion/src/debugger.cpp index 975a3929ce77a..21d2b1322a418 100644 --- a/perception/autoware_image_projection_based_fusion/src/debugger.cpp +++ b/perception/autoware_image_projection_based_fusion/src/debugger.cpp @@ -14,6 +14,10 @@ #include "autoware/image_projection_based_fusion/debugger.hpp" +#include +#include +#include + #if __has_include() #include #else diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 16a089fcc6d09..067deb5d03a87 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -24,6 +24,9 @@ #include #include +#include +#include +#include #ifdef ROS_DISTRO_GALACTIC #include diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index ac9ed88c2d98c..4e0f88e2134ac 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -29,6 +29,9 @@ #include #include +#include +#include +#include namespace { diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp index 205d231ab32bd..e3813a020e319 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp @@ -16,6 +16,8 @@ #include +#include + namespace autoware::image_projection_based_fusion { diff --git a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp index e925efdc0afcb..9a94613a2b788 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp @@ -20,6 +20,12 @@ #include #include +#include +#include +#include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #include diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 3a67d37c415c8..da9d413757332 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -19,6 +19,11 @@ #include #include +#include +#include +#include +#include + namespace autoware::image_projection_based_fusion { diff --git a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index 1f362da89f7a8..f9eb4ef909282 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -17,6 +17,8 @@ #include "autoware/image_projection_based_fusion/utils/geometry.hpp" #include "autoware/image_projection_based_fusion/utils/utils.hpp" +#include + #ifdef ROS_DISTRO_GALACTIC #include #include diff --git a/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp index 430b452b391f6..e678a956bc64e 100644 --- a/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp @@ -19,6 +19,9 @@ #include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #include diff --git a/perception/autoware_image_projection_based_fusion/src/utils/geometry.cpp b/perception/autoware_image_projection_based_fusion/src/utils/geometry.cpp index 4bea6ac0fe713..a5a86cc0eb3a6 100644 --- a/perception/autoware_image_projection_based_fusion/src/utils/geometry.cpp +++ b/perception/autoware_image_projection_based_fusion/src/utils/geometry.cpp @@ -16,6 +16,8 @@ #include +#include + namespace autoware::image_projection_based_fusion { diff --git a/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp b/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp index 912f6e99355e4..338a5605e5a79 100644 --- a/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/autoware_image_projection_based_fusion/src/utils/utils.cpp @@ -16,6 +16,10 @@ #include +#include +#include +#include + namespace autoware::image_projection_based_fusion { bool checkCameraInfo(const sensor_msgs::msg::CameraInfo & camera_info) diff --git a/perception/autoware_image_projection_based_fusion/test/test_geometry.cpp b/perception/autoware_image_projection_based_fusion/test/test_geometry.cpp index cf3778e7a0c84..b51ad06eb7b88 100644 --- a/perception/autoware_image_projection_based_fusion/test/test_geometry.cpp +++ b/perception/autoware_image_projection_based_fusion/test/test_geometry.cpp @@ -16,6 +16,8 @@ #include +#include + TEST(objectToVertices, test_objectToVertices) { // Test `boundingBoxToVertices()` and `cylinderToVertices()` simultaneously diff --git a/perception/autoware_image_projection_based_fusion/test/test_utils.cpp b/perception/autoware_image_projection_based_fusion/test/test_utils.cpp index ac179c66dd3d0..79dd775928f41 100644 --- a/perception/autoware_image_projection_based_fusion/test/test_utils.cpp +++ b/perception/autoware_image_projection_based_fusion/test/test_utils.cpp @@ -17,6 +17,8 @@ #include +#include + using autoware::point_types::PointXYZI; void setPointCloud2Fields(sensor_msgs::msg::PointCloud2 & pointcloud) diff --git a/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp b/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp index 86b1bf10c75a1..60aa09c8e16d7 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp @@ -22,8 +22,11 @@ #include #include +#include +#include #include #include +#include #include namespace autoware diff --git a/perception/autoware_lidar_apollo_instance_segmentation/src/feature_generator.cpp b/perception/autoware_lidar_apollo_instance_segmentation/src/feature_generator.cpp index e1aa0fc0494de..fa70863d9c800 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/src/feature_generator.cpp +++ b/perception/autoware_lidar_apollo_instance_segmentation/src/feature_generator.cpp @@ -17,6 +17,7 @@ #include "autoware/lidar_apollo_instance_segmentation/log_table.hpp" #include +#include namespace { diff --git a/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp b/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp index 3314b1c7421d3..9a3e13b81120f 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp +++ b/perception/autoware_lidar_apollo_instance_segmentation/src/node.cpp @@ -19,6 +19,8 @@ #include #include +#include + namespace autoware { namespace lidar_apollo_instance_segmentation diff --git a/perception/autoware_lidar_centerpoint/lib/detection_class_remapper.cpp b/perception/autoware_lidar_centerpoint/lib/detection_class_remapper.cpp index 80c842f8746a4..f2806bb84282b 100644 --- a/perception/autoware_lidar_centerpoint/lib/detection_class_remapper.cpp +++ b/perception/autoware_lidar_centerpoint/lib/detection_class_remapper.cpp @@ -14,6 +14,9 @@ #include "autoware/lidar_centerpoint/detection_class_remapper.hpp" +#include +#include + namespace autoware::lidar_centerpoint { diff --git a/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp b/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp index d0c0bb156f4a2..7767c0b5cbb02 100644 --- a/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp +++ b/perception/autoware_lidar_centerpoint/lib/network/network_trt.cpp @@ -14,6 +14,9 @@ #include "autoware/lidar_centerpoint/network/network_trt.hpp" +#include +#include + namespace autoware::lidar_centerpoint { bool VoxelEncoderTRT::setProfile( diff --git a/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp b/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp index 8f3f0fa9b20e2..9764d20628f24 100644 --- a/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp @@ -18,6 +18,8 @@ #include #include +#include + namespace autoware::lidar_centerpoint { diff --git a/perception/autoware_lidar_centerpoint/lib/preprocess/voxel_generator.cpp b/perception/autoware_lidar_centerpoint/lib/preprocess/voxel_generator.cpp index f975449530e5c..208c96a369182 100644 --- a/perception/autoware_lidar_centerpoint/lib/preprocess/voxel_generator.cpp +++ b/perception/autoware_lidar_centerpoint/lib/preprocess/voxel_generator.cpp @@ -19,6 +19,7 @@ #include "sensor_msgs/point_cloud2_iterator.hpp" +#include #include namespace autoware::lidar_centerpoint diff --git a/perception/autoware_lidar_centerpoint/lib/ros_utils.cpp b/perception/autoware_lidar_centerpoint/lib/ros_utils.cpp index c76fa6567ab51..0ea681538d8c1 100644 --- a/perception/autoware_lidar_centerpoint/lib/ros_utils.cpp +++ b/perception/autoware_lidar_centerpoint/lib/ros_utils.cpp @@ -18,6 +18,9 @@ #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/math/constants.hpp" +#include +#include + namespace autoware::lidar_centerpoint { diff --git a/perception/autoware_lidar_centerpoint/test/test_detection_class_remapper.cpp b/perception/autoware_lidar_centerpoint/test/test_detection_class_remapper.cpp index 48642bf7227dc..ae893c38b8d6a 100644 --- a/perception/autoware_lidar_centerpoint/test/test_detection_class_remapper.cpp +++ b/perception/autoware_lidar_centerpoint/test/test_detection_class_remapper.cpp @@ -16,6 +16,8 @@ #include +#include + TEST(DetectionClassRemapperTest, MapClasses) { autoware::lidar_centerpoint::DetectionClassRemapper remapper; diff --git a/perception/autoware_lidar_centerpoint/test/test_nms.cpp b/perception/autoware_lidar_centerpoint/test/test_nms.cpp index 4a59d4dba98bf..fd9e78b0c6585 100644 --- a/perception/autoware_lidar_centerpoint/test/test_nms.cpp +++ b/perception/autoware_lidar_centerpoint/test/test_nms.cpp @@ -16,6 +16,8 @@ #include +#include + TEST(NonMaximumSuppressionTest, Apply) { autoware::lidar_centerpoint::NonMaximumSuppression nms; diff --git a/perception/autoware_lidar_centerpoint/test/test_ros_utils.cpp b/perception/autoware_lidar_centerpoint/test/test_ros_utils.cpp index 5605d2df6a9d9..d45d18f51cc4e 100644 --- a/perception/autoware_lidar_centerpoint/test/test_ros_utils.cpp +++ b/perception/autoware_lidar_centerpoint/test/test_ros_utils.cpp @@ -16,6 +16,9 @@ #include +#include +#include + TEST(TestSuite, box3DToDetectedObject) { std::vector class_names = {"CAR", "TRUCK", "BUS", "TRAILER", diff --git a/perception/autoware_lidar_centerpoint/test/test_voxel_generator.cpp b/perception/autoware_lidar_centerpoint/test/test_voxel_generator.cpp index a5b5337e3b24e..4b94cb983c862 100644 --- a/perception/autoware_lidar_centerpoint/test/test_voxel_generator.cpp +++ b/perception/autoware_lidar_centerpoint/test/test_voxel_generator.cpp @@ -18,6 +18,9 @@ #include "sensor_msgs/point_cloud2_iterator.hpp" +#include +#include + void VoxelGeneratorTest::SetUp() { // Setup things that should occur before every test instance should go here diff --git a/perception/autoware_lidar_transfusion/lib/detection_class_remapper.cpp b/perception/autoware_lidar_transfusion/lib/detection_class_remapper.cpp index 08bdc65e666de..661cf9b8cded4 100644 --- a/perception/autoware_lidar_transfusion/lib/detection_class_remapper.cpp +++ b/perception/autoware_lidar_transfusion/lib/detection_class_remapper.cpp @@ -14,6 +14,9 @@ #include +#include +#include + namespace autoware::lidar_transfusion { diff --git a/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp b/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp index 052b7627166f9..8e3cb8a55ec7e 100644 --- a/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp +++ b/perception/autoware_lidar_transfusion/lib/network/network_trt.cpp @@ -19,6 +19,8 @@ #include #include #include +#include +#include namespace autoware::lidar_transfusion { diff --git a/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp b/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp index 1ce151d2960ef..1a288d1b0fd44 100644 --- a/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp @@ -18,6 +18,8 @@ #include #include +#include + namespace autoware::lidar_transfusion { diff --git a/perception/autoware_lidar_transfusion/lib/preprocess/voxel_generator.cpp b/perception/autoware_lidar_transfusion/lib/preprocess/voxel_generator.cpp index 203a556d9057a..80ae1fae0eb1d 100644 --- a/perception/autoware_lidar_transfusion/lib/preprocess/voxel_generator.cpp +++ b/perception/autoware_lidar_transfusion/lib/preprocess/voxel_generator.cpp @@ -18,6 +18,9 @@ #include +#include +#include +#include #include namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/lib/ros_utils.cpp b/perception/autoware_lidar_transfusion/lib/ros_utils.cpp index 88f6497f8d656..82f95697100cd 100644 --- a/perception/autoware_lidar_transfusion/lib/ros_utils.cpp +++ b/perception/autoware_lidar_transfusion/lib/ros_utils.cpp @@ -18,6 +18,9 @@ #include #include +#include +#include + namespace autoware::lidar_transfusion { diff --git a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp index 09702099f001e..4e100f2e794d5 100644 --- a/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp +++ b/perception/autoware_lidar_transfusion/lib/transfusion_trt.cpp @@ -26,6 +26,7 @@ #include #include #include +#include #include namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp b/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp index fae1cc97404da..c75a5f434aeed 100644 --- a/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp +++ b/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp @@ -16,6 +16,11 @@ #include "autoware/lidar_transfusion/utils.hpp" +#include +#include +#include +#include + namespace autoware::lidar_transfusion { diff --git a/perception/autoware_lidar_transfusion/test/test_detection_class_remapper.cpp b/perception/autoware_lidar_transfusion/test/test_detection_class_remapper.cpp index a9b5c8e83fbf7..ed79d362ba73d 100644 --- a/perception/autoware_lidar_transfusion/test/test_detection_class_remapper.cpp +++ b/perception/autoware_lidar_transfusion/test/test_detection_class_remapper.cpp @@ -16,6 +16,8 @@ #include +#include + TEST(DetectionClassRemapperTest, MapClasses) { autoware::lidar_transfusion::DetectionClassRemapper remapper; diff --git a/perception/autoware_lidar_transfusion/test/test_nms.cpp b/perception/autoware_lidar_transfusion/test/test_nms.cpp index 654cb56078c57..5449f61aa2284 100644 --- a/perception/autoware_lidar_transfusion/test/test_nms.cpp +++ b/perception/autoware_lidar_transfusion/test/test_nms.cpp @@ -16,6 +16,8 @@ #include +#include + TEST(NonMaximumSuppressionTest, Apply) { autoware::lidar_transfusion::NonMaximumSuppression nms; diff --git a/perception/autoware_lidar_transfusion/test/test_postprocess_kernel.cpp b/perception/autoware_lidar_transfusion/test/test_postprocess_kernel.cpp index bc30ca04ebfe6..b09e85f0a9325 100644 --- a/perception/autoware_lidar_transfusion/test/test_postprocess_kernel.cpp +++ b/perception/autoware_lidar_transfusion/test/test_postprocess_kernel.cpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/test/test_preprocess_kernel.cpp b/perception/autoware_lidar_transfusion/test/test_preprocess_kernel.cpp index c4a1c37b4ff77..afc25024d122e 100644 --- a/perception/autoware_lidar_transfusion/test/test_preprocess_kernel.cpp +++ b/perception/autoware_lidar_transfusion/test/test_preprocess_kernel.cpp @@ -23,6 +23,7 @@ #include #include +#include #include namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/test/test_ros_utils.cpp b/perception/autoware_lidar_transfusion/test/test_ros_utils.cpp index ac9c4ca0378cb..31468b28f962a 100644 --- a/perception/autoware_lidar_transfusion/test/test_ros_utils.cpp +++ b/perception/autoware_lidar_transfusion/test/test_ros_utils.cpp @@ -16,6 +16,9 @@ #include +#include +#include + TEST(TestSuite, box3DToDetectedObject) { std::vector class_names = {"CAR", "TRUCK", "BUS", "TRAILER", diff --git a/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp b/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp index df546dbde6d97..3eccc4eac1e83 100644 --- a/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp +++ b/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp @@ -22,6 +22,9 @@ #include "sensor_msgs/point_cloud2_iterator.hpp" +#include +#include + namespace autoware::lidar_transfusion { 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 e2ccae19a04f7..42dbf5b83fa8c 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 @@ -46,8 +46,13 @@ #include #include #include +#include #include #include +#include +#include +#include +#include namespace autoware::map_based_prediction { diff --git a/perception/autoware_map_based_prediction/src/path_generator.cpp b/perception/autoware_map_based_prediction/src/path_generator.cpp index 57104082d0cf7..3bd6d62aba999 100644 --- a/perception/autoware_map_based_prediction/src/path_generator.cpp +++ b/perception/autoware_map_based_prediction/src/path_generator.cpp @@ -20,6 +20,9 @@ #include #include +#include +#include +#include namespace autoware::map_based_prediction { diff --git a/perception/autoware_map_based_prediction/src/predictor_vru.cpp b/perception/autoware_map_based_prediction/src/predictor_vru.cpp index 31630f7645171..0eea665cbd8a2 100644 --- a/perception/autoware_map_based_prediction/src/predictor_vru.cpp +++ b/perception/autoware_map_based_prediction/src/predictor_vru.cpp @@ -19,6 +19,15 @@ #include #include +#include +#include +#include +#include +#include +#include +#include +#include + namespace autoware::map_based_prediction { using autoware::universe_utils::ScopedTimeTrack; diff --git a/perception/autoware_map_based_prediction/src/utils.cpp b/perception/autoware_map_based_prediction/src/utils.cpp index 8c4a25a793bf7..cfc5036106daf 100644 --- a/perception/autoware_map_based_prediction/src/utils.cpp +++ b/perception/autoware_map_based_prediction/src/utils.cpp @@ -22,6 +22,15 @@ #include #include +#include +#include +#include +#include +#include +#include +#include +#include + namespace autoware::map_based_prediction { namespace utils diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/tracker_base.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/tracker_base.cpp index daa8db5db91e6..24e2b0c9f5acf 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/tracker_base.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/tracker_base.cpp @@ -20,6 +20,7 @@ #include #include +#include namespace { diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp index 399634b63bffe..89258835f920b 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/bicycle_motion_model.cpp @@ -28,6 +28,8 @@ #include #include +#include + namespace autoware::multi_object_tracker { diff --git a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp index 3f0b854931842..ddfdc7ef7cb10 100644 --- a/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp +++ b/perception/autoware_multi_object_tracker/lib/uncertainty/uncertainty_processor.cpp @@ -20,6 +20,8 @@ #include #include +#include + namespace autoware::multi_object_tracker { namespace uncertainty diff --git a/perception/autoware_multi_object_tracker/src/debugger/debug_object.cpp b/perception/autoware_multi_object_tracker/src/debugger/debug_object.cpp index 59f50bd2e9f0b..bc27525d85f55 100644 --- a/perception/autoware_multi_object_tracker/src/debugger/debug_object.cpp +++ b/perception/autoware_multi_object_tracker/src/debugger/debug_object.cpp @@ -20,8 +20,11 @@ #include #include +#include #include #include +#include +#include namespace { diff --git a/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp b/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp index 3e47bbe9bed8d..9d830bb9e5b81 100644 --- a/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp +++ b/perception/autoware_multi_object_tracker/src/debugger/debugger.cpp @@ -14,7 +14,10 @@ #include "debugger.hpp" +#include #include +#include +#include namespace autoware::multi_object_tracker { 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 68a356cd91da5..d55ff3ab1f0bb 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 @@ -31,6 +31,7 @@ #include #include +#include #include #include #include diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp index c9ee8dae9562a..5b8fd23999a95 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp @@ -17,6 +17,8 @@ #include #include +#include +#include namespace autoware::multi_object_tracker { diff --git a/perception/autoware_multi_object_tracker/src/processor/processor.cpp b/perception/autoware_multi_object_tracker/src/processor/processor.cpp index ba9b3d17fd20f..f4202c1f6e413 100644 --- a/perception/autoware_multi_object_tracker/src/processor/processor.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/processor.cpp @@ -20,6 +20,10 @@ #include "autoware_perception_msgs/msg/tracked_objects.hpp" #include +#include +#include +#include +#include namespace autoware::multi_object_tracker { diff --git a/perception/autoware_object_merger/src/object_association_merger_node.cpp b/perception/autoware_object_merger/src/object_association_merger_node.cpp index af9d0e15f4894..0e2b88f4aa566 100644 --- a/perception/autoware_object_merger/src/object_association_merger_node.cpp +++ b/perception/autoware_object_merger/src/object_association_merger_node.cpp @@ -25,8 +25,12 @@ #include #include +#include +#include +#include #include #include +#include using Label = autoware_perception_msgs::msg::ObjectClassification; diff --git a/perception/autoware_radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp b/perception/autoware_radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp index 93475af7b3628..9a0477befd5be 100644 --- a/perception/autoware_radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp +++ b/perception/autoware_radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp @@ -20,6 +20,8 @@ #include +#include + std::shared_ptr get_node(double angle_threshold, double velocity_threshold) { diff --git a/perception/autoware_radar_object_tracker/src/association/data_association.cpp b/perception/autoware_radar_object_tracker/src/association/data_association.cpp index 673ae084fb242..79c91a96c4cc8 100644 --- a/perception/autoware_radar_object_tracker/src/association/data_association.cpp +++ b/perception/autoware_radar_object_tracker/src/association/data_association.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include diff --git a/perception/autoware_radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp b/perception/autoware_radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp index 47b9430616fc9..04b2bd24d4b8d 100644 --- a/perception/autoware_radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp +++ b/perception/autoware_radar_object_tracker/src/tracker/model/constant_turn_rate_motion_tracker.cpp @@ -30,6 +30,9 @@ #include #include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/perception/autoware_radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp b/perception/autoware_radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp index 6facac3707c56..80b965ddb3840 100644 --- a/perception/autoware_radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp +++ b/perception/autoware_radar_object_tracker/src/tracker/model/linear_motion_tracker.cpp @@ -30,6 +30,9 @@ #include #include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/perception/autoware_radar_object_tracker/src/tracker/model/tracker_base.cpp b/perception/autoware_radar_object_tracker/src/tracker/model/tracker_base.cpp index ce63d96dfb83a..69a020a774372 100644 --- a/perception/autoware_radar_object_tracker/src/tracker/model/tracker_base.cpp +++ b/perception/autoware_radar_object_tracker/src/tracker/model/tracker_base.cpp @@ -20,6 +20,7 @@ #include #include +#include namespace autoware::radar_object_tracker { diff --git a/perception/autoware_radar_object_tracker/src/utils/radar_object_tracker_utils.cpp b/perception/autoware_radar_object_tracker/src/utils/radar_object_tracker_utils.cpp index f0a6a5dfd384d..cfbffdc089c11 100644 --- a/perception/autoware_radar_object_tracker/src/utils/radar_object_tracker_utils.cpp +++ b/perception/autoware_radar_object_tracker/src/utils/radar_object_tracker_utils.cpp @@ -14,6 +14,10 @@ #include "autoware_radar_object_tracker/utils/radar_object_tracker_utils.hpp" +#include +#include +#include + namespace autoware::radar_object_tracker::utils { diff --git a/perception/autoware_radar_object_tracker/src/utils/utils.cpp b/perception/autoware_radar_object_tracker/src/utils/utils.cpp index 351c4cfd21159..9ea4f0a36a9ac 100644 --- a/perception/autoware_radar_object_tracker/src/utils/utils.cpp +++ b/perception/autoware_radar_object_tracker/src/utils/utils.cpp @@ -14,6 +14,8 @@ #include "autoware_radar_object_tracker/utils/utils.hpp" +#include + namespace autoware::radar_object_tracker::utils { // concatenate matrices vertically diff --git a/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp b/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp index 62b6b9f3b09b5..e52fc57a5a20c 100644 --- a/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp +++ b/perception/autoware_raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp @@ -22,6 +22,8 @@ #include +#include + namespace autoware::low_intensity_cluster_filter { LowIntensityClusterFilter::LowIntensityClusterFilter(const rclcpp::NodeOptions & node_options) diff --git a/perception/autoware_raindrop_cluster_filter/test/test_low_intensity_cluster_filter.cpp b/perception/autoware_raindrop_cluster_filter/test/test_low_intensity_cluster_filter.cpp index e7644ce45e443..c53ca66db6720 100644 --- a/perception/autoware_raindrop_cluster_filter/test/test_low_intensity_cluster_filter.cpp +++ b/perception/autoware_raindrop_cluster_filter/test/test_low_intensity_cluster_filter.cpp @@ -24,6 +24,9 @@ #include +#include +#include +#include #include using autoware::low_intensity_cluster_filter::LowIntensityClusterFilter; diff --git a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp index 4cb8c0083a148..b4b1f18832da7 100644 --- a/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp +++ b/perception/autoware_shape_estimation/lib/tensorrt_shape_estimator.cpp @@ -18,8 +18,13 @@ #include +#include #include +#include +#include #include +#include +#include namespace autoware::shape_estimation { diff --git a/perception/autoware_shape_estimation/test/test_shape_estimation_node.cpp b/perception/autoware_shape_estimation/test/test_shape_estimation_node.cpp index df04ade05b1ce..a7554f8249785 100644 --- a/perception/autoware_shape_estimation/test/test_shape_estimation_node.cpp +++ b/perception/autoware_shape_estimation/test/test_shape_estimation_node.cpp @@ -22,6 +22,9 @@ #include +#include +#include + namespace { using autoware::shape_estimation::ShapeEstimationNode; diff --git a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/calibrator.hpp b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/calibrator.hpp index 3d5d6f6538b15..59833a348ba91 100644 --- a/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/calibrator.hpp +++ b/perception/autoware_tensorrt_classifier/include/autoware/tensorrt_classifier/calibrator.hpp @@ -47,7 +47,9 @@ #include #include +#include #include +#include #include #include #include diff --git a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp index 4ca70c2f75618..b24e4fe56e8b8 100644 --- a/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp +++ b/perception/autoware_tensorrt_classifier/src/tensorrt_classifier.cpp @@ -20,10 +20,12 @@ #include #include +#include #include #include #include #include +#include #include static void trimLeft(std::string & s) diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp index cf5ebdc525a89..5aa897983af72 100644 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/logger.hpp @@ -21,6 +21,7 @@ #include #include +#include #include #include #include diff --git a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp index 76a9fd8bab7a8..2b3b3f02f315f 100644 --- a/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp +++ b/perception/autoware_tensorrt_common/include/autoware/tensorrt_common/tensorrt_common.hpp @@ -17,6 +17,8 @@ #ifndef YOLOX_STANDALONE #include + +#include #endif #include diff --git a/perception/autoware_tensorrt_common/src/simple_profiler.cpp b/perception/autoware_tensorrt_common/src/simple_profiler.cpp index c538470711fb8..2bcc1c4f9da06 100644 --- a/perception/autoware_tensorrt_common/src/simple_profiler.cpp +++ b/perception/autoware_tensorrt_common/src/simple_profiler.cpp @@ -14,7 +14,10 @@ #include +#include #include +#include +#include namespace autoware { diff --git a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp index 632501c0dc057..897010d22bb4b 100644 --- a/perception/autoware_tensorrt_common/src/tensorrt_common.cpp +++ b/perception/autoware_tensorrt_common/src/tensorrt_common.cpp @@ -23,6 +23,7 @@ #include #include #include +#include namespace { diff --git a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/calibrator.hpp b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/calibrator.hpp index 46305b12c0de6..24698c1d90f72 100644 --- a/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/calibrator.hpp +++ b/perception/autoware_tensorrt_yolox/include/autoware/tensorrt_yolox/calibrator.hpp @@ -48,7 +48,9 @@ #include #include +#include #include +#include #include #include #include diff --git a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp index 451af305a4410..06540f2b7cd19 100644 --- a/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/autoware_tensorrt_yolox/src/tensorrt_yolox.cpp @@ -31,6 +31,7 @@ #include #include #include +#include #include namespace diff --git a/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp b/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp index 919d68202a9a9..243e82c65dab9 100644 --- a/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp +++ b/perception/autoware_tensorrt_yolox/src/yolox_single_image_inference_node.cpp @@ -15,6 +15,8 @@ #include #include +#include + #if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__))) #include namespace fs = ::std::filesystem; diff --git a/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp b/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp index eab815969ac9a..44912e2242eb2 100644 --- a/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp +++ b/perception/autoware_tracking_object_merger/src/decorative_tracker_merger_node.cpp @@ -28,7 +28,10 @@ #include #include +#include +#include #include +#include using Label = autoware_perception_msgs::msg::ObjectClassification; diff --git a/perception/autoware_tracking_object_merger/src/utils/tracker_state.cpp b/perception/autoware_tracking_object_merger/src/utils/tracker_state.cpp index 9fd5fda7a63bb..9b859113390af 100644 --- a/perception/autoware_tracking_object_merger/src/utils/tracker_state.cpp +++ b/perception/autoware_tracking_object_merger/src/utils/tracker_state.cpp @@ -16,6 +16,11 @@ #include "autoware/tracking_object_merger/utils/utils.hpp" +#include +#include +#include +#include + namespace autoware::tracking_object_merger { diff --git a/perception/autoware_tracking_object_merger/src/utils/utils.cpp b/perception/autoware_tracking_object_merger/src/utils/utils.cpp index 04d7f94f2886c..15d130b4fcd50 100644 --- a/perception/autoware_tracking_object_merger/src/utils/utils.cpp +++ b/perception/autoware_tracking_object_merger/src/utils/utils.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include diff --git a/perception/autoware_traffic_light_arbiter/src/signal_match_validator.cpp b/perception/autoware_traffic_light_arbiter/src/signal_match_validator.cpp index d964f8b2cd7ba..396ebd8816088 100644 --- a/perception/autoware_traffic_light_arbiter/src/signal_match_validator.cpp +++ b/perception/autoware_traffic_light_arbiter/src/signal_match_validator.cpp @@ -14,6 +14,12 @@ #include "autoware/traffic_light_arbiter/signal_match_validator.hpp" +#include +#include +#include +#include +#include + namespace util { using TrafficSignalArray = autoware_perception_msgs::msg::TrafficLightGroupArray; diff --git a/perception/autoware_traffic_light_arbiter/test/test_node.cpp b/perception/autoware_traffic_light_arbiter/test/test_node.cpp index 1419f8675d0fa..f993ad7cec84d 100644 --- a/perception/autoware_traffic_light_arbiter/test/test_node.cpp +++ b/perception/autoware_traffic_light_arbiter/test/test_node.cpp @@ -21,6 +21,10 @@ #include #include +#include +#include +#include +#include #include using autoware::TrafficLightArbiter; diff --git a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp index 76f5e608ca425..37ffca4a9526c 100644 --- a/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp +++ b/perception/autoware_traffic_light_fine_detector/src/traffic_light_fine_detector_node.cpp @@ -14,6 +14,8 @@ #include "traffic_light_fine_detector_node.hpp" +#include + #if (defined(_MSC_VER) or (defined(__GNUC__) and (7 <= __GNUC_MAJOR__))) #include namespace fs = ::std::filesystem; diff --git a/perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector_node.cpp b/perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector_node.cpp index d133fe0b443d1..5e74d77df644f 100644 --- a/perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector_node.cpp +++ b/perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector_node.cpp @@ -31,6 +31,11 @@ #include #include +#include +#include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp index 08c6600d91923..15211920bc7f2 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp +++ b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include #include 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 7fd5ac8489226..751e80e101e84 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.cpp +++ b/perception/autoware_traffic_light_occlusion_predictor/src/occlusion_predictor.cpp @@ -16,6 +16,8 @@ #include "occlusion_predictor.hpp" #include +#include +#include namespace { 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 d3ab30146a8b5..14b8d2e51c78d 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 @@ -19,6 +19,7 @@ #include #include +#include #include #include #include diff --git a/perception/perception_utils/src/run_length_encoder.cpp b/perception/perception_utils/src/run_length_encoder.cpp index fb7f5ba33b846..59430de5069e8 100644 --- a/perception/perception_utils/src/run_length_encoder.cpp +++ b/perception/perception_utils/src/run_length_encoder.cpp @@ -14,6 +14,8 @@ #include "perception_utils/run_length_encoder.hpp" +#include + namespace perception_utils { diff --git a/perception/perception_utils/test/test_utils.cpp b/perception/perception_utils/test/test_utils.cpp index d28b8489971e0..5d721c731935e 100644 --- a/perception/perception_utils/test/test_utils.cpp +++ b/perception/perception_utils/test/test_utils.cpp @@ -18,6 +18,8 @@ #include +#include + // Test case 1: Test if the decoded image is the same as the original image TEST(UtilsTest, runLengthEncoderDecoderTest) { From 1e5077cd8f7b878e34b6097f2516811ed2192d95 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:14:32 +0300 Subject: [PATCH 226/273] fix(cpplint): include what you use - planning (#9570) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../src/utils/objects_to_costmap.cpp | 1 + .../test/test_costmap_generator.cpp | 4 ++++ .../test/test_object_map_utils.cpp | 2 ++ .../test/test_objects_to_costmap.cpp | 2 ++ .../test/test_points_to_costmap.cpp | 2 ++ .../src/autoware_freespace_planner/utils.cpp | 3 +++ .../test/test_freespace_planner.cpp | 5 +++++ .../test/test_freespace_planner_node_interface.cpp | 1 + .../test/test_freespace_planner_utils.cpp | 1 + .../scripts/bind/astar_search_pybind.cpp | 3 +++ .../src/abstract_algorithm.cpp | 2 ++ .../src/astar_search.cpp | 3 +++ .../src/rrtstar.cpp | 2 ++ .../src/rrtstar_core.cpp | 3 +++ .../test/src/test_freespace_planning_algorithms.cpp | 2 ++ .../test/src/test_rrtstar_core_informed.cpp | 1 + .../src/lanelet2_plugins/utility_functions.cpp | 1 + .../src/mission_planner/mission_planner.cpp | 3 +++ .../test/test_lanelet2_plugins_default_planner.cpp | 4 ++++ .../test/test_utility_functions.cpp | 2 ++ .../src/marker_utils.cpp | 2 ++ .../src/objects_of_interest_marker_interface.cpp | 2 ++ planning/autoware_obstacle_cruise_planner/src/node.cpp | 7 +++++++ .../optimization_based_planner.cpp | 6 ++++++ .../optimization_based_planner/velocity_optimizer.cpp | 2 ++ .../src/pid_based_planner/pid_based_planner.cpp | 5 +++++ .../src/planner_interface.cpp | 4 ++++ .../src/polygon_utils.cpp | 5 +++++ planning/autoware_obstacle_cruise_planner/src/utils.cpp | 4 ++++ .../test/test_obstacle_cruise_planner_node_interface.cpp | 1 + .../test/test_obstacle_cruise_planner_utils.cpp | 3 +++ .../autoware_obstacle_stop_planner/src/debug_marker.cpp | 2 ++ .../autoware_obstacle_stop_planner/src/planner_utils.cpp | 3 +++ ...est_autoware_obstacle_stop_planner_node_interface.cpp | 1 + planning/autoware_path_optimizer/src/debug_marker.cpp | 3 +++ planning/autoware_path_optimizer/src/mpt_optimizer.cpp | 4 ++++ planning/autoware_path_optimizer/src/node.cpp | 3 +++ planning/autoware_path_optimizer/src/replan_checker.cpp | 1 + .../src/state_equation_generator.cpp | 2 ++ .../test/test_path_optimizer_node_interface.cpp | 1 + planning/autoware_path_smoother/src/elastic_band.cpp | 3 +++ .../autoware_path_smoother/src/elastic_band_smoother.cpp | 3 +++ planning/autoware_path_smoother/src/replan_checker.cpp | 1 + .../test/test_autoware_path_smoother_node_interface.cpp | 1 + .../autoware_planning_test_manager_utils.hpp | 1 + .../src/autoware_planning_test_manager.cpp | 5 +++++ .../src/path_to_trajectory.cpp | 2 ++ planning/autoware_planning_validator/src/utils.cpp | 1 + .../test/src/test_planning_validator_functions.cpp | 1 + .../test/src/test_planning_validator_node_interface.cpp | 1 + .../test/src/test_planning_validator_pubsub.cpp | 3 +++ planning/autoware_route_handler/src/route_handler.cpp | 2 ++ .../autoware_route_handler/test/test_route_handler.hpp | 1 + planning/autoware_rtc_interface/src/rtc_interface.cpp | 3 +++ .../autoware_rtc_interface/test/test_rtc_interface.cpp | 3 +++ .../test_autoware_scenario_selector_node_interface.cpp | 1 + .../bag_ego_trajectory_based_centerline.cpp | 1 + .../optimization_trajectory_based_centerline.cpp | 1 + .../autoware_static_centerline_generator/src/main.cpp | 3 +++ .../src/static_centerline_generator_node.cpp | 1 + .../autoware_static_centerline_generator/src/utils.cpp | 3 +++ .../src/debug_marker.cpp | 2 ++ planning/autoware_surround_obstacle_checker/src/node.cpp | 1 + .../test/test_surround_obstacle_checker.cpp | 3 +++ planning/autoware_velocity_smoother/src/node.cpp | 1 + .../analytical_jerk_constrained_smoother.cpp | 1 + .../src/smoother/jerk_filtered_smoother.cpp | 2 ++ .../src/smoother/l2_pseudo_jerk_smoother.cpp | 1 + .../src/smoother/linf_pseudo_jerk_smoother.cpp | 1 + .../src/smoother/smoother_base.cpp | 2 ++ .../test/test_velocity_smoother_node_interface.cpp | 1 + .../src/interface.cpp | 1 + .../src/scene.cpp | 1 + .../test/test_behavior_path_planner_node_interface.cpp | 2 ++ .../scene.hpp | 1 + .../src/scene.cpp | 2 ++ .../test/test_behavior_path_planner_node_interface.cpp | 2 ++ .../src/manager.cpp | 2 ++ .../test/test_behavior_path_planner_node_interface.cpp | 2 ++ .../examples/plot_map.cpp | 8 ++++++++ .../src/decision_state.cpp | 3 +++ .../src/goal_planner_module.cpp | 5 +++++ .../src/goal_searcher.cpp | 2 ++ .../src/pull_over_planner/pull_over_planner_base.cpp | 3 +++ .../src/pull_over_planner/shift_pull_over.cpp | 3 +++ .../src/util.cpp | 4 ++++ .../test/test_util.cpp | 4 ++++ .../src/interface.cpp | 2 ++ .../src/manager.cpp | 1 + .../src/scene.cpp | 1 + .../src/utils/markers.cpp | 1 + .../test/test_behavior_path_planner_node_interface.cpp | 2 ++ .../test/test_lane_change_scene.cpp | 2 ++ .../src/planner_manager.cpp | 5 +++++ .../autoware_behavior_path_planner/test/input.cpp | 2 ++ ...est_autoware_behavior_path_planner_node_interface.cpp | 2 ++ .../autoware_behavior_path_planner/test/test_utils.cpp | 2 ++ .../src/interface/scene_module_interface.cpp | 2 ++ .../src/interface/scene_module_manager_interface.cpp | 4 ++++ .../src/interface/scene_module_visitor.cpp | 2 ++ .../src/marker_utils/utils.cpp | 2 ++ .../src/turn_signal_decider.cpp | 4 ++++ .../drivable_area_expansion/drivable_area_expansion.cpp | 4 ++++ .../src/utils/drivable_area_expansion/map_utils.cpp | 2 ++ .../drivable_area_expansion/static_drivable_area.cpp | 8 ++++++++ .../parking_departure/geometric_parallel_parking.cpp | 3 +++ .../src/utils/parking_departure/utils.cpp | 5 +++++ .../src/utils/path_safety_checker/objects_filtering.cpp | 4 ++++ .../src/utils/path_safety_checker/safety_check.cpp | 4 ++++ .../src/utils/path_shifter/path_shifter.cpp | 1 + .../src/utils/path_utils.cpp | 2 ++ .../src/utils/traffic_light_utils.cpp | 3 +++ .../src/utils/utils.cpp | 2 ++ .../test/test_drivable_area_expansion.cpp | 2 ++ .../test/test_objects_filtering.cpp | 1 + .../test/test_parking_departure_utils.cpp | 3 +++ .../test/test_path_shifter.cpp | 3 +++ .../test/test_path_utils.cpp | 1 + .../test/test_static_drivable_area.cpp | 1 + .../test/test_utils.cpp | 2 ++ .../src/sampling_planner_module.cpp | 9 +++++++++ .../src/scene.cpp | 1 + .../test/test_behavior_path_planner_node_interface.cpp | 2 ++ .../test/test_side_shift_utils.cpp | 2 ++ .../src/freespace_pull_out.cpp | 2 ++ .../src/geometric_pull_out.cpp | 4 ++++ .../src/shift_pull_out.cpp | 3 +++ .../src/start_planner_module.cpp | 4 ++++ .../src/debug.cpp | 2 ++ .../src/scene.cpp | 1 + .../src/shift_line_generator.cpp | 5 +++++ .../src/utils.cpp | 1 + .../test/test_behavior_path_planner_node_interface.cpp | 2 ++ .../test/test_utils.cpp | 3 +++ .../src/debug.cpp | 1 + .../src/scene_crosswalk.cpp | 2 ++ .../src/scene_crosswalk.hpp | 1 + .../src/util.cpp | 1 + .../test/test_crosswalk.cpp | 2 ++ .../src/utils.cpp | 2 ++ .../src/debug.cpp | 2 ++ .../src/decision_result.cpp | 2 ++ .../src/object_manager.cpp | 2 ++ .../src/scene_intersection.cpp | 3 +++ .../src/scene_intersection_collision.cpp | 8 ++++++++ .../src/scene_intersection_occlusion.cpp | 4 ++++ .../src/scene_intersection_prepare_data.cpp | 7 +++++++ .../src/scene_intersection_stuck.cpp | 4 ++++ .../src/scene_merge_from_private_road.cpp | 1 + .../src/util.cpp | 1 + .../test/test_util.cpp | 2 ++ .../src/manager.cpp | 1 + .../src/util.cpp | 1 + .../src/utils.cpp | 1 + .../src/grid_utils.cpp | 1 + .../src/occlusion_spot_utils.cpp | 1 + .../src/scene_occlusion_spot.cpp | 1 + .../test/src/test_grid_utils.cpp | 2 ++ .../test/src/test_occlusion_spot_utils.cpp | 3 +++ .../autoware_behavior_velocity_planner/src/node.cpp | 2 ++ .../test/src/test_node_interface.cpp | 2 ++ .../src/scene_module_interface.cpp | 2 ++ .../src/utilization/debug.cpp | 3 +++ .../src/utilization/trajectory_utils.cpp | 4 ++++ .../src/utilization/util.cpp | 3 +++ .../test/src/test_utilization.cpp | 1 + .../src/debug.cpp | 3 +++ .../src/dynamic_obstacle.cpp | 2 ++ .../src/manager.cpp | 1 + .../src/path_utils.cpp | 3 +++ .../src/scene.cpp | 2 ++ .../src/state_machine.cpp | 2 ++ .../src/utils.cpp | 2 ++ .../src/scene.cpp | 3 +++ .../src/scene.cpp | 1 + .../src/scene.cpp | 2 ++ .../src/utils.cpp | 2 ++ .../src/debug.cpp | 2 ++ .../src/utils.cpp | 2 ++ .../test/test_utils.cpp | 2 ++ .../src/scene_walkway.cpp | 1 + .../src/object_stop_decision.cpp | 1 + .../benchmarks/collision_checker_benchmark.cpp | 1 + .../src/debug.cpp | 1 + .../src/map_utils.cpp | 2 ++ .../src/obstacle_velocity_limiter.cpp | 1 + .../src/obstacle_velocity_limiter_module.cpp | 3 +++ .../test/test_forward_projection.cpp | 1 + .../src/collision_checker.cpp | 4 ++++ .../test/test_collision_checker.cpp | 2 ++ .../autoware_motion_velocity_planner_node/src/node.cpp | 1 + .../src/planner_manager.cpp | 1 + .../test/src/test_node_interface.cpp | 2 ++ .../autoware_bezier_sampler/src/bezier.cpp | 3 +++ .../autoware_bezier_sampler/src/bezier_sampling.cpp | 2 ++ .../src/frenet_planner/frenet_planner.cpp | 1 + .../autoware_path_sampler/src/node.cpp | 3 +++ .../autoware_path_sampler/src/prepare_inputs.cpp | 1 + .../src/sampler_common/transform/spline_transform.cpp | 1 + .../autoware_sampler_common/test/test_transform.cpp | 2 ++ 200 files changed, 471 insertions(+) diff --git a/planning/autoware_costmap_generator/src/utils/objects_to_costmap.cpp b/planning/autoware_costmap_generator/src/utils/objects_to_costmap.cpp index bcd2e15fe9ca7..64f558b4f5604 100644 --- a/planning/autoware_costmap_generator/src/utils/objects_to_costmap.cpp +++ b/planning/autoware_costmap_generator/src/utils/objects_to_costmap.cpp @@ -50,6 +50,7 @@ #include #include +#include #include #include diff --git a/planning/autoware_costmap_generator/test/test_costmap_generator.cpp b/planning/autoware_costmap_generator/test/test_costmap_generator.cpp index 00c35e2514f43..f0db05b6fdd6f 100644 --- a/planning/autoware_costmap_generator/test/test_costmap_generator.cpp +++ b/planning/autoware_costmap_generator/test/test_costmap_generator.cpp @@ -20,6 +20,10 @@ #include +#include +#include +#include + using autoware::costmap_generator::CostmapGenerator; using tier4_planning_msgs::msg::Scenario; diff --git a/planning/autoware_costmap_generator/test/test_object_map_utils.cpp b/planning/autoware_costmap_generator/test/test_object_map_utils.cpp index a20c2326d2757..5225b089f845f 100644 --- a/planning/autoware_costmap_generator/test/test_object_map_utils.cpp +++ b/planning/autoware_costmap_generator/test/test_object_map_utils.cpp @@ -17,6 +17,8 @@ #include +#include + namespace { grid_map::GridMap construct_gridmap( diff --git a/planning/autoware_costmap_generator/test/test_objects_to_costmap.cpp b/planning/autoware_costmap_generator/test/test_objects_to_costmap.cpp index 4ab5a32e77028..83f7055531e7d 100644 --- a/planning/autoware_costmap_generator/test/test_objects_to_costmap.cpp +++ b/planning/autoware_costmap_generator/test/test_objects_to_costmap.cpp @@ -19,6 +19,8 @@ #include #include +#include + namespace { geometry_msgs::msg::Point32 toPoint32(const geometry_msgs::msg::Pose & pose) diff --git a/planning/autoware_costmap_generator/test/test_points_to_costmap.cpp b/planning/autoware_costmap_generator/test/test_points_to_costmap.cpp index b98479f43c2aa..ecfeaaf6ac676 100644 --- a/planning/autoware_costmap_generator/test/test_points_to_costmap.cpp +++ b/planning/autoware_costmap_generator/test/test_points_to_costmap.cpp @@ -16,6 +16,8 @@ #include +#include + namespace autoware::costmap_generator { using pointcloud = pcl::PointCloud; diff --git a/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp b/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp index 2e0c461ae71c0..a08c62723c3d5 100644 --- a/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp +++ b/planning/autoware_freespace_planner/src/autoware_freespace_planner/utils.cpp @@ -16,6 +16,9 @@ #include +#include +#include + namespace autoware::freespace_planner::utils { diff --git a/planning/autoware_freespace_planner/test/test_freespace_planner.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner.cpp index add449c66eb0d..bccf417503edb 100644 --- a/planning/autoware_freespace_planner/test/test_freespace_planner.cpp +++ b/planning/autoware_freespace_planner/test/test_freespace_planner.cpp @@ -25,6 +25,11 @@ #include #include +#include +#include +#include +#include + using autoware::freespace_planner::FreespacePlannerNode; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; 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 f43b4401865b2..8bf30757aafb7 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 @@ -20,6 +20,7 @@ #include +#include #include using autoware::freespace_planner::FreespacePlannerNode; diff --git a/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp b/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp index 534278a3b8dc8..e374c4056df1e 100644 --- a/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp +++ b/planning/autoware_freespace_planner/test/test_freespace_planner_utils.cpp @@ -19,6 +19,7 @@ #include #include +#include #include using autoware::freespace_planner::utils::Odometry; diff --git a/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp b/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp index f2003e438f5bf..7808d18f24aed 100644 --- a/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp +++ b/planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp @@ -24,6 +24,9 @@ #include #include +#include +#include + namespace autoware::freespace_planning_algorithms { struct PlannerWaypointsVector diff --git a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp index b968e70bd2c01..56d6526e26272 100644 --- a/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/abstract_algorithm.cpp @@ -19,6 +19,8 @@ #include #include +#include +#include #include #include diff --git a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp index 3fecf800f1bf6..0a17b112eed6f 100644 --- a/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/astar_search.cpp @@ -24,6 +24,9 @@ #include #include +#include +#include +#include #ifdef ROS_DISTRO_GALACTIC #include diff --git a/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp b/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp index 000b118214d9e..0427381db7de8 100644 --- a/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/rrtstar.cpp @@ -16,6 +16,8 @@ #include "autoware/freespace_planning_algorithms/kinematic_bicycle_model.hpp" +#include + namespace autoware::freespace_planning_algorithms { rrtstar_core::Pose poseMsgToPose(const geometry_msgs::msg::Pose & pose_msg) diff --git a/planning/autoware_freespace_planning_algorithms/src/rrtstar_core.cpp b/planning/autoware_freespace_planning_algorithms/src/rrtstar_core.cpp index 853d9ef0a9787..6affc862cc64e 100644 --- a/planning/autoware_freespace_planning_algorithms/src/rrtstar_core.cpp +++ b/planning/autoware_freespace_planning_algorithms/src/rrtstar_core.cpp @@ -16,13 +16,16 @@ #include +#include #include #include #include #include #include +#include #include #include +#include // cspell: ignore rsspace // In this case, RSSpace means "Reeds Shepp state Space" diff --git a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp index a46b8bba58920..c343a8773f8ad 100644 --- a/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp +++ b/planning/autoware_freespace_planning_algorithms/test/src/test_freespace_planning_algorithms.cpp @@ -29,6 +29,8 @@ #include #include #include +#include +#include #include #include #include diff --git a/planning/autoware_freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp b/planning/autoware_freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp index 40181884d36c7..a7a66123b7856 100644 --- a/planning/autoware_freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp +++ b/planning/autoware_freespace_planning_algorithms/test/src/test_rrtstar_core_informed.cpp @@ -18,6 +18,7 @@ #include #include +#include namespace autoware::freespace_planning_algorithms::rrtstar_core { diff --git a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp index 08345282a9264..40bccd118965f 100644 --- a/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/autoware_mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -23,6 +23,7 @@ #include #include +#include namespace autoware::mission_planner::lanelet2 { diff --git a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp index 521beb8f7dcd5..cbbcfb84d2cbb 100644 --- a/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/autoware_mission_planner/src/mission_planner/mission_planner.cpp @@ -27,7 +27,10 @@ #include #include +#include +#include #include +#include namespace autoware::mission_planner { diff --git a/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp b/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp index 124a04e3e4ed2..8da26ab851bb4 100644 --- a/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp +++ b/planning/autoware_mission_planner/test/test_lanelet2_plugins_default_planner.cpp @@ -29,6 +29,10 @@ #include #include +#include +#include +#include + using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::createQuaternionFromRPY; using autoware_planning_msgs::msg::LaneletRoute; diff --git a/planning/autoware_mission_planner/test/test_utility_functions.cpp b/planning/autoware_mission_planner/test/test_utility_functions.cpp index 6cde09b7664a2..da44a2ad17cf0 100644 --- a/planning/autoware_mission_planner/test/test_utility_functions.cpp +++ b/planning/autoware_mission_planner/test/test_utility_functions.cpp @@ -23,6 +23,8 @@ #include #include +#include + using autoware::mission_planner::lanelet2::convert_linear_ring_to_polygon; using autoware::mission_planner::lanelet2::convertBasicPoint3dToPose; using autoware::mission_planner::lanelet2::convertCenterlineToPoints; diff --git a/planning/autoware_objects_of_interest_marker_interface/src/marker_utils.cpp b/planning/autoware_objects_of_interest_marker_interface/src/marker_utils.cpp index 42d92bd0c91da..f2f076869e2ff 100644 --- a/planning/autoware_objects_of_interest_marker_interface/src/marker_utils.cpp +++ b/planning/autoware_objects_of_interest_marker_interface/src/marker_utils.cpp @@ -14,6 +14,8 @@ #include "autoware/objects_of_interest_marker_interface/marker_utils.hpp" +#include + namespace autoware::objects_of_interest_marker_interface::marker_utils { using geometry_msgs::msg::Point; diff --git a/planning/autoware_objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp b/planning/autoware_objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp index 253d2ec05c246..cbdb2542b97e7 100644 --- a/planning/autoware_objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp +++ b/planning/autoware_objects_of_interest_marker_interface/src/objects_of_interest_marker_interface.cpp @@ -18,6 +18,8 @@ #include #include +#include + namespace autoware::objects_of_interest_marker_interface { using autoware_perception_msgs::msg::Shape; diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index a6a029530b1a5..8275f2a1cd7d4 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -32,6 +32,13 @@ #include #include +#include +#include +#include +#include +#include +#include +#include namespace { diff --git a/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp b/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp index 7bf0f67129a20..62edf82beec5a 100644 --- a/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp @@ -25,6 +25,12 @@ #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/ros/marker_helper.hpp" +#include +#include +#include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp b/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp index 8e31411bfb4af..39a35204cda8f 100644 --- a/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp @@ -16,7 +16,9 @@ #include +#include #include +#include VelocityOptimizer::VelocityOptimizer( const double max_s_weight, const double max_v_weight, const double over_s_safety_weight, diff --git a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp index da5d083d6ddcf..f8982ed3fec2a 100644 --- a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp @@ -23,6 +23,11 @@ #include "tier4_planning_msgs/msg/velocity_limit.hpp" +#include +#include +#include +#include + using autoware::signal_processing::LowpassFilter1d; namespace diff --git a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp index bfff561e3ffe2..b08bb10ef69cf 100644 --- a/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp @@ -25,8 +25,12 @@ #include #include +#include +#include #include #include +#include +#include namespace { diff --git a/planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp b/planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp index 639feec856a7e..4d6e6568067f4 100644 --- a/planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp @@ -18,6 +18,11 @@ #include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" +#include +#include +#include +#include + namespace { PointWithStamp calcNearestCollisionPoint( diff --git a/planning/autoware_obstacle_cruise_planner/src/utils.cpp b/planning/autoware_obstacle_cruise_planner/src/utils.cpp index 3bf6ee311ca13..dd4373c115fe0 100644 --- a/planning/autoware_obstacle_cruise_planner/src/utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/utils.cpp @@ -17,6 +17,10 @@ #include "autoware/object_recognition_utils/predicted_path_utils.hpp" #include "autoware/universe_utils/ros/marker_helper.hpp" +#include +#include +#include + namespace obstacle_cruise_utils { namespace diff --git a/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp b/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp index ef5f695756b7e..2235704a3a070 100644 --- a/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp +++ b/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp @@ -20,6 +20,7 @@ #include +#include #include using autoware::motion_planning::ObstacleCruisePlannerNode; diff --git a/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_utils.cpp b/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_utils.cpp index f7dbd60596507..b32508cc2c50e 100644 --- a/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_utils.cpp @@ -21,6 +21,9 @@ #include +#include +#include + StopObstacle generate_stop_obstacle(uint8_t label, double dist) { const std::string uuid{}; diff --git a/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp b/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp index 71077014a2be1..93526518306af 100644 --- a/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp +++ b/planning/autoware_obstacle_stop_planner/src/debug_marker.cpp @@ -18,6 +18,8 @@ #include #include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/autoware_obstacle_stop_planner/src/planner_utils.cpp b/planning/autoware_obstacle_stop_planner/src/planner_utils.cpp index 28c5523f49620..5cdb48a9d6a70 100644 --- a/planning/autoware_obstacle_stop_planner/src/planner_utils.cpp +++ b/planning/autoware_obstacle_stop_planner/src/planner_utils.cpp @@ -31,6 +31,9 @@ #include #include +#include +#include +#include namespace autoware::motion_planning { diff --git a/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp b/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp index 99a1ab46d2304..9f840586a1959 100644 --- a/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp +++ b/planning/autoware_obstacle_stop_planner/test/test_autoware_obstacle_stop_planner_node_interface.cpp @@ -20,6 +20,7 @@ #include +#include #include using autoware::motion_planning::ObstacleStopPlannerNode; diff --git a/planning/autoware_path_optimizer/src/debug_marker.cpp b/planning/autoware_path_optimizer/src/debug_marker.cpp index 397c334eca5b7..cf994dadf38cc 100644 --- a/planning/autoware_path_optimizer/src/debug_marker.cpp +++ b/planning/autoware_path_optimizer/src/debug_marker.cpp @@ -18,6 +18,9 @@ #include "visualization_msgs/msg/marker_array.hpp" +#include +#include + namespace autoware::path_optimizer { using autoware::universe_utils::appendMarkerArray; diff --git a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp index df07f3f98957a..bff3b78b6ba7d 100644 --- a/planning/autoware_path_optimizer/src/mpt_optimizer.cpp +++ b/planning/autoware_path_optimizer/src/mpt_optimizer.cpp @@ -26,8 +26,12 @@ #include #include #include +#include #include +#include #include +#include +#include namespace autoware::path_optimizer { diff --git a/planning/autoware_path_optimizer/src/node.cpp b/planning/autoware_path_optimizer/src/node.cpp index 98bc05d0fe1cf..9d0345e304235 100644 --- a/planning/autoware_path_optimizer/src/node.cpp +++ b/planning/autoware_path_optimizer/src/node.cpp @@ -25,6 +25,9 @@ #include #include #include +#include +#include +#include namespace autoware::path_optimizer { diff --git a/planning/autoware_path_optimizer/src/replan_checker.cpp b/planning/autoware_path_optimizer/src/replan_checker.cpp index 11e31bfd2d459..a52fbcc78211f 100644 --- a/planning/autoware_path_optimizer/src/replan_checker.cpp +++ b/planning/autoware_path_optimizer/src/replan_checker.cpp @@ -19,6 +19,7 @@ #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/ros/update_param.hpp" +#include #include namespace autoware::path_optimizer diff --git a/planning/autoware_path_optimizer/src/state_equation_generator.cpp b/planning/autoware_path_optimizer/src/state_equation_generator.cpp index 74033c5834db2..6bb95d665c8d5 100644 --- a/planning/autoware_path_optimizer/src/state_equation_generator.cpp +++ b/planning/autoware_path_optimizer/src/state_equation_generator.cpp @@ -16,6 +16,8 @@ #include "autoware/path_optimizer/mpt_optimizer.hpp" +#include + namespace autoware::path_optimizer { // state equation: x = B u + W (u includes x_0) diff --git a/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp b/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp index 9d24702cf75ea..e310fecf15d8c 100644 --- a/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp +++ b/planning/autoware_path_optimizer/test/test_path_optimizer_node_interface.cpp @@ -20,6 +20,7 @@ #include +#include #include TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) diff --git a/planning/autoware_path_smoother/src/elastic_band.cpp b/planning/autoware_path_smoother/src/elastic_band.cpp index 0bdf83c9d3b7c..20786b7b3601e 100644 --- a/planning/autoware_path_smoother/src/elastic_band.cpp +++ b/planning/autoware_path_smoother/src/elastic_band.cpp @@ -27,6 +27,9 @@ #include #include #include +#include +#include +#include namespace { diff --git a/planning/autoware_path_smoother/src/elastic_band_smoother.cpp b/planning/autoware_path_smoother/src/elastic_band_smoother.cpp index a3082a2c979c3..2569faa4b8232 100644 --- a/planning/autoware_path_smoother/src/elastic_band_smoother.cpp +++ b/planning/autoware_path_smoother/src/elastic_band_smoother.cpp @@ -22,6 +22,9 @@ #include #include +#include +#include +#include namespace autoware::path_smoother { diff --git a/planning/autoware_path_smoother/src/replan_checker.cpp b/planning/autoware_path_smoother/src/replan_checker.cpp index 5d2e7a05e4b17..5739aa7481831 100644 --- a/planning/autoware_path_smoother/src/replan_checker.cpp +++ b/planning/autoware_path_smoother/src/replan_checker.cpp @@ -19,6 +19,7 @@ #include "autoware/universe_utils/geometry/geometry.hpp" #include "autoware/universe_utils/ros/update_param.hpp" +#include #include namespace autoware::path_smoother diff --git a/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp index 7c92763f94521..7402541c727ff 100644 --- a/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp +++ b/planning/autoware_path_smoother/test/test_autoware_path_smoother_node_interface.cpp @@ -20,6 +20,7 @@ #include +#include #include TEST(PlanningModuleInterfaceTest, NodeTestWithExceptionTrajectory) diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp index 63ad2ecce09cc..b61c579df83b9 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp @@ -22,6 +22,7 @@ #include #include +#include #include #include diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 02e64e3ec84a0..62f89cab44e7b 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -19,6 +19,11 @@ #include #include +#include +#include +#include +#include + namespace autoware::planning_test_manager { diff --git a/planning/autoware_planning_topic_converter/src/path_to_trajectory.cpp b/planning/autoware_planning_topic_converter/src/path_to_trajectory.cpp index ff2f3084fc9ba..76bb660259323 100644 --- a/planning/autoware_planning_topic_converter/src/path_to_trajectory.cpp +++ b/planning/autoware_planning_topic_converter/src/path_to_trajectory.cpp @@ -17,6 +17,8 @@ #include #include +#include + namespace autoware::planning_topic_converter { namespace diff --git a/planning/autoware_planning_validator/src/utils.cpp b/planning/autoware_planning_validator/src/utils.cpp index 0a70b4d415dcb..4304cd6146647 100644 --- a/planning/autoware_planning_validator/src/utils.cpp +++ b/planning/autoware_planning_validator/src/utils.cpp @@ -17,6 +17,7 @@ #include #include +#include #include #include #include diff --git a/planning/autoware_planning_validator/test/src/test_planning_validator_functions.cpp b/planning/autoware_planning_validator/test/src/test_planning_validator_functions.cpp index 9282392197665..6b0370fd6cf23 100644 --- a/planning/autoware_planning_validator/test/src/test_planning_validator_functions.cpp +++ b/planning/autoware_planning_validator/test/src/test_planning_validator_functions.cpp @@ -19,6 +19,7 @@ #include +#include #include using autoware::planning_validator::PlanningValidator; diff --git a/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp b/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp index 6476086c67730..2cf03e04311f2 100644 --- a/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp +++ b/planning/autoware_planning_validator/test/src/test_planning_validator_node_interface.cpp @@ -20,6 +20,7 @@ #include +#include #include using autoware::planning_test_manager::PlanningInterfaceTestManager; diff --git a/planning/autoware_planning_validator/test/src/test_planning_validator_pubsub.cpp b/planning/autoware_planning_validator/test/src/test_planning_validator_pubsub.cpp index a83fa1fd965fe..882ff09cfa33a 100644 --- a/planning/autoware_planning_validator/test/src/test_planning_validator_pubsub.cpp +++ b/planning/autoware_planning_validator/test/src/test_planning_validator_pubsub.cpp @@ -22,7 +22,10 @@ #include +#include #include +#include +#include #include /* diff --git a/planning/autoware_route_handler/src/route_handler.cpp b/planning/autoware_route_handler/src/route_handler.cpp index ec5f7bb5e0080..01e52d85f01c3 100644 --- a/planning/autoware_route_handler/src/route_handler.cpp +++ b/planning/autoware_route_handler/src/route_handler.cpp @@ -35,9 +35,11 @@ #include #include +#include #include #include #include +#include #include #include #include diff --git a/planning/autoware_route_handler/test/test_route_handler.hpp b/planning/autoware_route_handler/test/test_route_handler.hpp index 69d6a871959ca..1b15b539e2001 100644 --- a/planning/autoware_route_handler/test/test_route_handler.hpp +++ b/planning/autoware_route_handler/test/test_route_handler.hpp @@ -31,6 +31,7 @@ #include +#include #include #include namespace autoware::route_handler::test diff --git a/planning/autoware_rtc_interface/src/rtc_interface.cpp b/planning/autoware_rtc_interface/src/rtc_interface.cpp index 6b3a6c7406d39..47bc278c30564 100644 --- a/planning/autoware_rtc_interface/src/rtc_interface.cpp +++ b/planning/autoware_rtc_interface/src/rtc_interface.cpp @@ -14,6 +14,9 @@ #include "autoware/rtc_interface/rtc_interface.hpp" +#include +#include + namespace { using tier4_rtc_msgs::msg::Module; diff --git a/planning/autoware_rtc_interface/test/test_rtc_interface.cpp b/planning/autoware_rtc_interface/test/test_rtc_interface.cpp index 69efae3987677..d4b0195186282 100644 --- a/planning/autoware_rtc_interface/test/test_rtc_interface.cpp +++ b/planning/autoware_rtc_interface/test/test_rtc_interface.cpp @@ -22,6 +22,9 @@ #include +#include +#include + using tier4_rtc_msgs::msg::State; namespace autoware::rtc_interface diff --git a/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp b/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp index 3d5da19cbabbc..ef9af48967a11 100644 --- a/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp +++ b/planning/autoware_scenario_selector/test/test_autoware_scenario_selector_node_interface.cpp @@ -21,6 +21,7 @@ #include #include +#include #include namespace autoware::scenario_selector { diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp index cbfcac5789812..dc950f190652b 100644 --- a/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/bag_ego_trajectory_based_centerline.cpp @@ -22,6 +22,7 @@ #include #include +#include namespace autoware::static_centerline_generator { diff --git a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp index 1f72dea1cd35f..51725fb8a3799 100644 --- a/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp +++ b/planning/autoware_static_centerline_generator/src/centerline_source/optimization_trajectory_based_centerline.cpp @@ -23,6 +23,7 @@ #include "utils.hpp" #include +#include namespace autoware::static_centerline_generator { diff --git a/planning/autoware_static_centerline_generator/src/main.cpp b/planning/autoware_static_centerline_generator/src/main.cpp index 5afc7e58ba52b..811d57c6036ef 100644 --- a/planning/autoware_static_centerline_generator/src/main.cpp +++ b/planning/autoware_static_centerline_generator/src/main.cpp @@ -14,6 +14,9 @@ #include "static_centerline_generator_node.hpp" +#include +#include + int main(int argc, char * argv[]) { rclcpp::init(argc, argv); diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index 398edc215da3e..7f0264d02434e 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -51,6 +51,7 @@ #include #include #include +#include #include #include #include diff --git a/planning/autoware_static_centerline_generator/src/utils.cpp b/planning/autoware_static_centerline_generator/src/utils.cpp index c045a50fec0d7..f84fe79cec288 100644 --- a/planning/autoware_static_centerline_generator/src/utils.cpp +++ b/planning/autoware_static_centerline_generator/src/utils.cpp @@ -23,7 +23,10 @@ #include #include +#include +#include #include +#include namespace autoware::static_centerline_generator { diff --git a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp index 6a5883fbd660d..bbd1cac04ed89 100644 --- a/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp +++ b/planning/autoware_surround_obstacle_checker/src/debug_marker.cpp @@ -17,6 +17,8 @@ #include #include #include + +#include #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index 382281127a113..0adca312ca733 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -32,6 +32,7 @@ #include #include +#include #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp b/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp index 1122a37bb2672..3951532ed0df0 100644 --- a/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp +++ b/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp @@ -20,6 +20,9 @@ #include +#include +#include + namespace autoware::surround_obstacle_checker { auto generateTestTargetNode() -> std::shared_ptr diff --git a/planning/autoware_velocity_smoother/src/node.cpp b/planning/autoware_velocity_smoother/src/node.cpp index f47c84ab54b01..1e0f6119ac21e 100644 --- a/planning/autoware_velocity_smoother/src/node.cpp +++ b/planning/autoware_velocity_smoother/src/node.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include // clang-format on diff --git a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp index 213e70283f9b1..fcbcde84fe1ea 100644 --- a/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.cpp @@ -19,6 +19,7 @@ #include "autoware/velocity_smoother/trajectory_utils.hpp" #include +#include #include #include #include diff --git a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp index b218a662de175..0f61171a3bb70 100644 --- a/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/jerk_filtered_smoother.cpp @@ -22,7 +22,9 @@ #include #include #include +#include #include +#include #include #include diff --git a/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp index 678c8e01bf67e..3280512376a58 100644 --- a/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/l2_pseudo_jerk_smoother.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp b/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp index 60345ff0fa6f4..eaad896562ccd 100644 --- a/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/linf_pseudo_jerk_smoother.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp index 5360da101ee8c..e4271a9c387de 100644 --- a/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp +++ b/planning/autoware_velocity_smoother/src/smoother/smoother_base.cpp @@ -24,6 +24,8 @@ #include #include +#include +#include #include namespace autoware::velocity_smoother diff --git a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp index d384c319ee361..b590af1b3ee0a 100644 --- a/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp +++ b/planning/autoware_velocity_smoother/test/test_velocity_smoother_node_interface.cpp @@ -20,6 +20,7 @@ #include +#include #include using autoware::planning_test_manager::PlanningInterfaceTestManager; diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp index 0e0b0fcf63933..3080ba1045b41 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp @@ -19,6 +19,7 @@ #include #include +#include namespace autoware::behavior_path_planner { diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp index 991b5c8af656d..7e4bc4d5ba6ac 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp @@ -31,6 +31,7 @@ #include #include +#include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index cdefc7f82125a..f679efacb6a44 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -21,6 +21,8 @@ #include #include +#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp index 33d33119602f5..44b56f4ea0990 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/include/autoware/behavior_path_dynamic_obstacle_avoidance_module/scene.hpp @@ -28,6 +28,7 @@ #include #include +#include #include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp index c162170ae5eb0..dc7efebe88fba 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/src/scene.cpp @@ -36,6 +36,8 @@ #include #include #include +#include +#include #include namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index fc0fac5ff7b9d..a18a2440dcb3a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -18,6 +18,8 @@ #include #include +#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp index c04914ed1c72b..45c997f364633 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/src/manager.cpp @@ -17,6 +17,8 @@ #include "autoware/behavior_path_lane_change_module/interface.hpp" #include "scene.hpp" +#include + namespace autoware::behavior_path_planner { using autoware::behavior_path_planner::LaneChangeInterface; diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 4a5fb562eb140..ad37a90605233 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -20,6 +20,8 @@ #include #include +#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp index af64dc5220010..40c2bd201abc7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/examples/plot_map.cpp @@ -41,9 +41,17 @@ #include #include +#include #include #include +#include #include +#include +#include +#include +#include +#include +#include using namespace std::chrono_literals; // NOLINT diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp index 827e1269cfa80..1a4a6e5a25589 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp @@ -17,6 +17,9 @@ #include #include +#include +#include + namespace autoware::behavior_path_planner { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 6b216e83833c4..120a2fa6c24ec 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -37,10 +37,15 @@ #include #include +#include +#include #include +#include #include #include #include +#include +#include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp index 5607729e1030d..66192a00a99fa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -29,7 +29,9 @@ #include +#include #include +#include #include namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/pull_over_planner_base.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/pull_over_planner_base.cpp index 63610f5ac31f7..31d8afffbdabe 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/pull_over_planner_base.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/pull_over_planner_base.cpp @@ -14,6 +14,9 @@ #include +#include +#include + namespace autoware::behavior_path_planner { diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp index 4bdec4a285d75..501502125d7ee 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp @@ -22,7 +22,10 @@ #include #include +#include +#include #include +#include #include namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index 75cdb2d892510..8ca9d9ab45dc3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -33,7 +33,11 @@ #include #include +#include +#include #include +#include +#include #include namespace autoware::behavior_path_planner::goal_planner_utils diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp index 64dbac4ff9adf..de231b78041b4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/test/test_util.cpp @@ -20,6 +20,10 @@ #include +#include +#include +#include + class TestUtilWithMap : public ::testing::Test { protected: diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 44252bb9f2005..77bf32512c0dc 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -24,8 +24,10 @@ #include #include +#include #include #include +#include #include namespace autoware::behavior_path_planner 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 fc419f149e2b9..b193ce33b17fa 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 @@ -20,6 +20,7 @@ #include +#include #include #include #include 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 03c161d40d58a..8769547550852 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 @@ -42,6 +42,7 @@ #include #include #include +#include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp index 5700842780395..ff0bd4437c21c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/markers.cpp @@ -26,6 +26,7 @@ #include #include +#include #include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp index 504de657eabda..555657fe34af9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_behavior_path_planner_node_interface.cpp @@ -20,6 +20,8 @@ #include #include +#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp index 3becc2e4f4a69..510fef2c07d7c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp @@ -25,7 +25,9 @@ #include +#include #include +#include using autoware::behavior_path_planner::FilteredLanesObjects; using autoware::behavior_path_planner::LaneChangeModuleManager; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp index bd5b391127467..041b7ad20a107 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/src/planner_manager.cpp @@ -25,8 +25,13 @@ #include +#include +#include #include #include +#include +#include +#include namespace autoware::behavior_path_planner { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/test/input.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/test/input.cpp index f4f368008c472..d1602432b19c2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/test/input.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/test/input.cpp @@ -13,6 +13,8 @@ // limitations under the License. #include "input.hpp" +#include + namespace autoware::behavior_path_planner { using autoware_planning_msgs::msg::PathPoint; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp index b7d992d9254dc..63b7ccf3fff12 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_autoware_behavior_path_planner_node_interface.cpp @@ -21,6 +21,8 @@ #include #include +#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_utils.cpp index 36e2914571c1f..3d6a76f6807a9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/test/test_utils.cpp @@ -23,6 +23,8 @@ #include #include +#include + using autoware::behavior_path_planner::PathWithLaneId; using autoware::behavior_path_planner::Pose; using autoware::behavior_path_planner::utils::FrenetPoint; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp index a6c480e130d7a..d7ecda3b92680 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_interface.cpp @@ -14,6 +14,8 @@ #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" +#include + namespace autoware::behavior_path_planner { void SceneModuleInterface::setDrivableLanes(const std::vector & drivable_lanes) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp index 7b362d9a8bafa..b91db3a740cfe 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_manager_interface.cpp @@ -14,6 +14,10 @@ #include "autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp" +#include +#include +#include + namespace autoware::behavior_path_planner { void SceneModuleManagerInterface::initInterface( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_visitor.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_visitor.cpp index 454d8753b0e62..e6ccfc74866c4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_visitor.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/interface/scene_module_visitor.cpp @@ -16,6 +16,8 @@ #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" +#include + namespace autoware::behavior_path_planner { std::shared_ptr SceneModuleVisitor::getAvoidanceModuleDebugMsg() const diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp index 90693aa65e661..7029c15e45b6e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/marker_utils/utils.cpp @@ -27,6 +27,8 @@ #include #include +#include +#include namespace marker_utils { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp index 22d80da2cfa67..d513017c221cf 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/turn_signal_decider.cpp @@ -26,10 +26,14 @@ #include #include +#include #include +#include #include +#include #include #include +#include namespace autoware::behavior_path_planner { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 648bb0a17622c..1076af002fb28 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -30,7 +30,11 @@ #include +#include +#include #include +#include +#include namespace autoware::behavior_path_planner::drivable_area_expansion { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp index 280060334cfd4..4cd7467997669 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp @@ -20,6 +20,8 @@ #include #include +#include +#include namespace autoware::behavior_path_planner::drivable_area_expansion { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp index 1c6295f3e70ef..0768c620dd054 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp @@ -29,6 +29,14 @@ #include #include +#include +#include +#include +#include +#include +#include +#include + namespace { template diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp index b18858e9dad04..789741153bf4a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp @@ -27,6 +27,9 @@ #include +#include +#include +#include #include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp index 5fea6b501ba24..18dee25919f98 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -19,6 +19,11 @@ #include #include +#include +#include +#include +#include + namespace autoware::behavior_path_planner::utils::parking_departure { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 3c1d9f194aeec..1caf287ee5386 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -23,6 +23,10 @@ #include #include +#include +#include +#include +#include namespace autoware::behavior_path_planner::utils::path_safety_checker::filter { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index 04b61b86dfa02..5ae62f51bdb52 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -28,8 +28,12 @@ #include +#include #include #include +#include +#include +#include namespace autoware::behavior_path_planner::utils::path_safety_checker { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp index 4fe7765366c08..6d15f387fba72 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_shifter/path_shifter.cpp @@ -20,6 +20,7 @@ #include #include +#include #include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp index 1e2ad668bf28f..8195b49ae662c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_utils.cpp @@ -27,7 +27,9 @@ #include #include +#include #include +#include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp index c31bddd921f99..305519279a9ea 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/traffic_light_utils.cpp @@ -16,6 +16,9 @@ #include #include +#include +#include + namespace autoware::behavior_path_planner::utils::traffic_light { using autoware::motion_utils::calcSignedArcLength; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp index a224ef16bc0d9..9b99a5ef7b31d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp @@ -33,7 +33,9 @@ #include #include #include +#include #include +#include #include namespace diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp index 21784757e469e..b8e3cca852a0a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp @@ -21,6 +21,8 @@ #include #include +#include + using autoware::behavior_path_planner::drivable_area_expansion::LineString2d; using autoware::behavior_path_planner::drivable_area_expansion::Point2d; using autoware::behavior_path_planner::drivable_area_expansion::Segment2d; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp index e7280c5bc150b..8c732a972a212 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_objects_filtering.cpp @@ -26,6 +26,7 @@ #include #include +#include #include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_parking_departure_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_parking_departure_utils.cpp index 4cb1b8ef14d5a..2b43cdaebd14d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_parking_departure_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_parking_departure_utils.cpp @@ -23,6 +23,9 @@ #include #include +#include +#include +#include constexpr double epsilon = 1e-6; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_path_shifter.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_path_shifter.cpp index 25fc533fc53a4..eacd1b086cd3b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_path_shifter.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_path_shifter.cpp @@ -21,6 +21,9 @@ #include +#include +#include + namespace autoware::behavior_path_planner { diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_path_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_path_utils.cpp index d96b30cccdfaa..562e8abfd432a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_path_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_path_utils.cpp @@ -22,6 +22,7 @@ #include #include +#include using tier4_planning_msgs::msg::PathWithLaneId; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_static_drivable_area.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_static_drivable_area.cpp index ba3141a89b26a..ab6076b328d14 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_static_drivable_area.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_static_drivable_area.cpp @@ -32,6 +32,7 @@ #include #include +#include const auto intersection_map = autoware::test_utils::make_map_bin_msg(autoware::test_utils::get_absolute_path_to_lanelet_map( diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp index 2234574fce83e..13fec41092cc8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_utils.cpp @@ -22,7 +22,9 @@ #include #include +#include #include +#include using autoware::universe_utils::Point2d; using autoware_perception_msgs::msg::PredictedObject; diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp index ede912ea1c285..fac3cc92de1d6 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/src/sampling_planner_module.cpp @@ -14,6 +14,15 @@ #include "autoware/behavior_path_sampling_planner_module/sampling_planner_module.hpp" +#include +#include +#include +#include +#include +#include +#include +#include + namespace autoware::behavior_path_planner { using autoware::motion_utils::calcSignedArcLength; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp index d640e5fc16771..22ee7ab77e077 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/src/scene.cpp @@ -26,6 +26,7 @@ #include #include #include +#include namespace autoware::behavior_path_planner { diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp index 1d70f1388d80b..c8661cdf1d912 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_behavior_path_planner_node_interface.cpp @@ -21,6 +21,8 @@ #include #include +#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_side_shift_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_side_shift_utils.cpp index d6aa91d1f9095..b5bb54a6586ca 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_side_shift_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/test/test_side_shift_utils.cpp @@ -19,6 +19,8 @@ #include #include +#include + namespace autoware::behavior_path_planner { diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp index f257904e141b6..42698f799c6b3 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/freespace_pull_out.cpp @@ -21,6 +21,8 @@ #include +#include +#include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp index 13a9908b97daf..bbc6c05725434 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/geometric_pull_out.cpp @@ -22,6 +22,10 @@ #include +#include +#include +#include + using autoware::motion_utils::findNearestIndex; using autoware::universe_utils::calcDistance2d; using autoware::universe_utils::calcOffsetPose; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp index aa3246eb3dac0..4759559619870 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/shift_pull_out.cpp @@ -25,7 +25,10 @@ #include #include +#include +#include #include +#include #include using autoware::motion_utils::findNearestIndex; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 210afdcd7c1ea..20cac638cebbd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -34,9 +34,13 @@ #include #include +#include +#include +#include #include #include #include +#include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp index 997fb7353b14c..e7177768be3dd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/debug.cpp @@ -20,6 +20,8 @@ #include #include +#include +#include #include #include diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index f7fc4ee48d364..76bfa621ac0e4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include namespace autoware::behavior_path_planner diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp index 917736b1680db..744af35641a59 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/shift_line_generator.cpp @@ -17,6 +17,11 @@ #include "autoware/behavior_path_planner_common/utils/utils.hpp" #include "autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp" +#include +#include +#include +#include + namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance { diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index cc036b687b105..c3d494c8ffe5d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp index 8cf5696a89372..b6a8fd04f93db 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_behavior_path_planner_node_interface.cpp @@ -18,6 +18,8 @@ #include #include +#include +#include #include using autoware::behavior_path_planner::BehaviorPathPlannerNode; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp index 7b0cef7e00bb6..6911be800bdc2 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp @@ -26,6 +26,9 @@ #include #include +#include +#include + namespace autoware::behavior_path_planner::utils::static_obstacle_avoidance { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp index 06ed75c99124b..2a6f4825ba414 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/debug.cpp @@ -24,6 +24,7 @@ #include #include +#include namespace autoware::behavior_velocity_planner { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp index b0ea73a2781d4..1bea0626b0b2f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp @@ -35,7 +35,9 @@ #include #include #include +#include #include +#include #include namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp index d27aebe42d459..8577ed1669b48 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp @@ -39,6 +39,7 @@ #include #include +#include #include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp index a72c866a85cef..50de1b1a8e1ff 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/util.cpp @@ -34,6 +34,7 @@ #include #include #include +#include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_crosswalk.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_crosswalk.cpp index b626ef1772853..8af879578ed89 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_crosswalk.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/test/test_crosswalk.cpp @@ -16,6 +16,8 @@ #include +#include + TEST(CrosswalkTest, CheckInterpolateEgoPassMargin) { namespace bvp = autoware::behavior_velocity_planner; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/utils.cpp index 6b3bf416e6d99..0d721fc81bcee 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/utils.cpp @@ -22,7 +22,9 @@ #include #include +#include #include +#include namespace { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp index ffffa4da8f4a1..e50bc041cbc89 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/debug.cpp @@ -22,6 +22,8 @@ #include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/decision_result.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/decision_result.cpp index c211e1f43783e..bfdc36afa9011 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/decision_result.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/decision_result.cpp @@ -14,6 +14,8 @@ #include "decision_result.hpp" +#include + namespace autoware::behavior_velocity_planner { std::string formatDecisionResult( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/object_manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/object_manager.cpp index d93fbf271aa1d..9fd5ba4ab7d5c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/object_manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/object_manager.cpp @@ -25,6 +25,8 @@ #include #include +#include +#include #include namespace diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp index cedc3c41e8165..6f7841ebb0bbb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -36,6 +36,9 @@ #include #include #include +#include +#include +#include #include namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp index 54af88c2f0fbb..5a66bec15bab1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_collision.cpp @@ -30,6 +30,14 @@ #include #include +#include +#include +#include +#include +#include +#include +#include + namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp index ec174be990e66..bbe76702a5faf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp @@ -23,7 +23,11 @@ #include +#include +#include #include +#include +#include namespace autoware::behavior_velocity_planner { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp index 402f3c1d22cc7..70e1d219c0d31 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp @@ -31,6 +31,13 @@ #include #include +#include +#include +#include +#include +#include +#include + namespace autoware::universe_utils { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp index 78365bc5e500f..35f4e3b34dbee 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_stuck.cpp @@ -26,6 +26,10 @@ #include #include +#include +#include +#include + namespace { lanelet::LineString3d getLineStringFromArcLength( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index 478576a5c6676..3dfdcc36c0cff 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp index 6474435afa26e..5c9b74a9ad3bd 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/util.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include namespace autoware::behavior_velocity_planner::util diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp index 6ee31c3712b47..959481493ccfe 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/test/test_util.cpp @@ -20,6 +20,8 @@ #include +#include + TEST(TestUtil, retrievePathsBackward) { /* diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp index 9cb37a899063d..9cb1153a8edd2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/manager.cpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp index 25315fd397aa4..7da73a313da79 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/util.cpp @@ -23,6 +23,7 @@ #include #include +#include namespace autoware::behavior_velocity_planner { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/utils.cpp index 526a6baf0dd30..5ce56d756e919 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/utils.cpp @@ -26,6 +26,7 @@ #include #include +#include namespace autoware::behavior_velocity_planner::no_stopping_area { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp index 783970c701262..b3e9b2678189f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/grid_utils.cpp @@ -15,6 +15,7 @@ #include "grid_utils.hpp" #include +#include #include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp index 56a5acd8c7dc4..baf15cbebce81 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp @@ -24,6 +24,7 @@ #include #include +#include #include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp index dfc2dca7afc21..522e83390b0f1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp @@ -30,6 +30,7 @@ #include #include +#include #include // turn on only when debugging. diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp index 6bc9423b6dc96..73fba3969442e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_grid_utils.cpp @@ -21,7 +21,9 @@ #include #include +#include #include +#include struct indexHash { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp index 0322bda0a88c9..8fee8ee783fa2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/test/src/test_occlusion_spot_utils.cpp @@ -22,6 +22,9 @@ #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/vector3.hpp" +#include +#include + using Point = geometry_msgs::msg::Point; using Vector3 = geometry_msgs::msg::Vector3; using DynamicObjects = autoware_perception_msgs::msg::PredictedObjects; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp index 2b921028c499a..d78bc883e6b35 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp @@ -28,6 +28,8 @@ #include #include #include + +#include #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp index 1dfa3163b5b6f..fe79450d0def8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/test/src/test_node_interface.cpp @@ -21,6 +21,8 @@ #include #include +#include +#include #include using autoware::behavior_velocity_planner::BehaviorVelocityPlannerNode; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp index fb19c4955c12a..cdfde1ce51205 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/scene_module_interface.cpp @@ -22,6 +22,8 @@ #include #include #include +#include +#include namespace autoware::behavior_velocity_planner { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp index dfd201bac707c..7fe87bd285309 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp @@ -15,6 +15,9 @@ #include #include #include + +#include +#include namespace autoware::behavior_velocity_planner { namespace debug diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index 6815ca3ff8cb4..72a6d29e7ba06 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -25,6 +25,10 @@ #include +#include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp index 88186a5b904b0..1b1c47dc6fbb7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp @@ -25,6 +25,9 @@ #include #include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp index ca5c57fd522c9..d3664f2b46ffc 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp @@ -22,6 +22,7 @@ #include #include +#include #define DEBUG_PRINT_PATH(path) \ { \ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp index 983a371234ccf..2823648e184d3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/debug.cpp @@ -20,6 +20,9 @@ #include #include +#include +#include + using autoware::universe_utils::appendMarkerArray; using autoware::universe_utils::calcOffsetPose; using autoware::universe_utils::createDefaultMarker; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp index 74b1ca490f752..a15f232b75a37 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp @@ -28,7 +28,9 @@ #include #include +#include #include +#include namespace autoware::behavior_velocity_planner { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp index f294e698ba8c2..4a16f263d0a54 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/manager.cpp @@ -16,6 +16,7 @@ #include +#include #include #include #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp index cf3c0fd7e10e1..e4e08d69a79f7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/path_utils.cpp @@ -15,6 +15,9 @@ #include "path_utils.hpp" #include + +#include +#include namespace autoware::behavior_velocity_planner::run_out_utils { /** diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp index 32bf81ed63598..a32a65a0d8909 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -32,7 +32,9 @@ #include #include +#include #include +#include namespace autoware::behavior_velocity_planner { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/state_machine.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/state_machine.cpp index 0a23d2218feb0..dafb4e6da097b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/state_machine.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/state_machine.cpp @@ -14,6 +14,8 @@ #include "state_machine.hpp" +#include + namespace autoware::behavior_velocity_planner { namespace run_out_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp index c32d38da2db33..9a9a49c3cb081 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/src/utils.cpp @@ -25,6 +25,8 @@ #include #include +#include +#include #ifdef ROS_DISTRO_GALACTIC #include diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp index 2ac8f1c477620..54ea807f3268b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/src/scene.cpp @@ -20,6 +20,9 @@ #include +#include +#include + namespace autoware::behavior_velocity_planner { using autoware::motion_utils::calcSignedArcLength; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index 8a06b9ba5f82d..4d8dea94583bb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -21,6 +21,7 @@ #include #include +#include namespace autoware::behavior_velocity_planner { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp index 76f1a19bfc69a..5eb0d5aa5f267 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp @@ -25,6 +25,8 @@ #include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp index 4f0829c901915..9b13123380ce1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp @@ -19,6 +19,8 @@ #include #include +#include + namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp index 2be77b2731fe0..2b4acd7ff0ca9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/debug.cpp @@ -18,6 +18,8 @@ #include #include #include + +#include using autoware::motion_utils::createStopVirtualWallMarker; using autoware::universe_utils::appendMarkerArray; using autoware::universe_utils::createDefaultMarker; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/utils.cpp index 940e29f0a0c0e..a1950bf768f4c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/utils.cpp @@ -20,6 +20,8 @@ #include #include +#include +#include namespace autoware::behavior_velocity_planner::virtual_traffic_light { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_utils.cpp index dd01b1be7fb83..e6bfa0234951c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/test/test_utils.cpp @@ -19,7 +19,9 @@ #include +#include #include +#include using autoware::behavior_velocity_planner::virtual_traffic_light::calcCenter; using autoware::behavior_velocity_planner::virtual_traffic_light::calcHeadPose; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp index 42a235a67edd1..6a7505930a334 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp @@ -18,6 +18,7 @@ #include #include +#include namespace autoware::behavior_velocity_planner { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp index 3f544c792d8e6..21726c43e12d6 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_stop_decision.cpp @@ -17,6 +17,7 @@ #include #include +#include namespace autoware::motion_velocity_planner::dynamic_obstacle_stop { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp index 020b15ba5133b..79b817c51169c 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/benchmarks/collision_checker_benchmark.cpp @@ -17,6 +17,7 @@ #include #include +#include using autoware::motion_velocity_planner::obstacle_velocity_limiter::CollisionChecker; using autoware::motion_velocity_planner::obstacle_velocity_limiter::linestring_t; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/debug.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/debug.cpp index 4d9859dba90da..ea83aafebfbb7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/debug.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/debug.cpp @@ -20,6 +20,7 @@ #include #include +#include namespace autoware::motion_velocity_planner::obstacle_velocity_limiter { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/map_utils.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/map_utils.cpp index 1796c65b42de0..c0894673d81f3 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/map_utils.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/map_utils.cpp @@ -23,6 +23,8 @@ #include #include +#include +#include namespace autoware::motion_velocity_planner::obstacle_velocity_limiter { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp index 1f788a73a3f42..e501b756af6a1 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp @@ -23,6 +23,7 @@ #include #include +#include namespace autoware::motion_velocity_planner::obstacle_velocity_limiter { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp index 35135089c0c8c..3fa3ec7cbf782 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp @@ -33,6 +33,9 @@ #include #include +#include +#include +#include namespace autoware::motion_velocity_planner { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_forward_projection.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_forward_projection.cpp index 0b8aad36580e6..d7b8e128b3cee 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_forward_projection.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_forward_projection.cpp @@ -24,6 +24,7 @@ #include #include +#include constexpr auto EPS = 1e-15; constexpr auto EPS_APPROX = 1e-3; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp index 6e84b63a3c7fc..f16c23efcb14c 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/src/collision_checker.cpp @@ -14,6 +14,10 @@ #include "autoware/motion_velocity_planner_common/collision_checker.hpp" +#include +#include +#include + namespace autoware::motion_velocity_planner { CollisionChecker::CollisionChecker(autoware::universe_utils::MultiPolygon2d trajectory_footprints) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp index 5988272b39ae1..d2a4a4560a430 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/test/test_collision_checker.cpp @@ -19,6 +19,8 @@ #include #include +#include +#include #include using autoware::motion_velocity_planner::CollisionChecker; diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp index 0e8a36977fec8..96865fec1c197 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include namespace diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp index 416ad215d5e25..b08798cbef772 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/planner_manager.cpp @@ -18,6 +18,7 @@ #include #include +#include namespace autoware::motion_velocity_planner { diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp index c35749ef33710..44ff7820c1566 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/test/src/test_node_interface.cpp @@ -20,6 +20,8 @@ #include +#include +#include #include using autoware::motion_velocity_planner::MotionVelocityPlannerNode; diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier.cpp b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier.cpp index 9a882ad06659a..e7a1901fc83ab 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier.cpp +++ b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier.cpp @@ -15,6 +15,9 @@ #include #include +#include +#include +#include namespace autoware::bezier_sampler { diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp index e9a1a9ef32de5..c36b8f88c8486 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp +++ b/planning/sampling_based_planner/autoware_bezier_sampler/src/bezier_sampling.cpp @@ -14,6 +14,8 @@ #include +#include + namespace autoware::bezier_sampler { std::vector sample( diff --git a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp index faabd0bcfdbe5..cab4acfbb8556 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp +++ b/planning/sampling_based_planner/autoware_frenet_planner/src/frenet_planner/frenet_planner.cpp @@ -30,6 +30,7 @@ #include #include #include +#include namespace autoware::frenet_planner { diff --git a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp index 34905f79cd364..fd07516d61bbf 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp @@ -27,8 +27,11 @@ #include +#include #include #include +#include +#include namespace autoware::path_sampler { diff --git a/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp index 127393abc5ac3..7f313318af236 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/prepare_inputs.cpp @@ -25,6 +25,7 @@ #include #include +#include #include #include #include diff --git a/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/transform/spline_transform.cpp b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/transform/spline_transform.cpp index ce473b1768a54..6c9447f25def0 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/transform/spline_transform.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/src/sampler_common/transform/spline_transform.cpp @@ -18,6 +18,7 @@ #include #include #include +#include namespace autoware::sampler_common::transform { diff --git a/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp b/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp index caf50473cde18..8229f5b9c9e41 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp +++ b/planning/sampling_based_planner/autoware_sampler_common/test/test_transform.cpp @@ -17,8 +17,10 @@ #include #include +#include #include #include +#include constexpr auto TOL = 1E-6; // 1µm tolerance From cbe13bf9b0ac11188c749e40cf65d102d4f009bb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:14:44 +0300 Subject: [PATCH 227/273] fix(cpplint): include what you use - sensing (#9571) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_image_diagnostics/src/image_diagnostics_node.cpp | 1 + .../src/gyro_bias_estimation_module.cpp | 2 ++ sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp | 2 ++ sensing/autoware_imu_corrector/src/imu_corrector_core.cpp | 3 +++ .../test/test_gyro_bias_estimation_module.cpp | 2 ++ .../src/blockage_diag/blockage_diag_node.cpp | 2 ++ .../concatenate_data/concatenate_and_time_sync_nodelet.cpp | 1 + .../src/crop_box_filter/crop_box_filter_node.cpp | 1 + .../src/distortion_corrector/distortion_corrector.cpp | 4 ++++ .../src/distortion_corrector/distortion_corrector_node.cpp | 4 ++++ .../downsample_filter/faster_voxel_grid_downsample_filter.cpp | 1 + .../pickup_based_voxel_grid_downsample_filter_node.cpp | 3 +++ .../src/downsample_filter/robin_hood.h | 3 ++- .../src/outlier_filter/ring_outlier_filter_node.cpp | 2 ++ .../src/polygon_remover/polygon_remover.cpp | 2 ++ .../src/time_synchronizer/time_synchronizer_node.cpp | 1 + .../autoware_pointcloud_preprocessor/src/utility/geometry.cpp | 2 ++ .../vector_map_filter/vector_map_inside_area_filter_node.cpp | 4 ++++ .../test/test_distortion_corrector_node.cpp | 4 ++++ .../test_radar_tracks_noise_filter_is_noise.cpp | 2 ++ .../src/vehicle_velocity_converter.cpp | 2 ++ 21 files changed, 47 insertions(+), 1 deletion(-) diff --git a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp index 829e0e3ee8d81..681e9ae70a89c 100644 --- a/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp +++ b/sensing/autoware_image_diagnostics/src/image_diagnostics_node.cpp @@ -16,6 +16,7 @@ #include +#include #include namespace autoware::image_diagnostics diff --git a/sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.cpp b/sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.cpp index 18d7965470f05..2fbd5d4a6a39e 100644 --- a/sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.cpp +++ b/sensing/autoware_imu_corrector/src/gyro_bias_estimation_module.cpp @@ -17,6 +17,8 @@ #include #include +#include + namespace autoware::imu_corrector { diff --git a/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp b/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp index ec91311455911..8dcc024ffc2b4 100644 --- a/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp +++ b/sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp @@ -19,7 +19,9 @@ #include #include +#include #include +#include namespace autoware::imu_corrector { diff --git a/sensing/autoware_imu_corrector/src/imu_corrector_core.cpp b/sensing/autoware_imu_corrector/src/imu_corrector_core.cpp index a9acb45888945..d615a721ca5eb 100644 --- a/sensing/autoware_imu_corrector/src/imu_corrector_core.cpp +++ b/sensing/autoware_imu_corrector/src/imu_corrector_core.cpp @@ -14,6 +14,9 @@ #include "imu_corrector_core.hpp" +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/sensing/autoware_imu_corrector/test/test_gyro_bias_estimation_module.cpp b/sensing/autoware_imu_corrector/test/test_gyro_bias_estimation_module.cpp index 573dbe84d6027..2d75c6d50de55 100644 --- a/sensing/autoware_imu_corrector/test/test_gyro_bias_estimation_module.cpp +++ b/sensing/autoware_imu_corrector/test/test_gyro_bias_estimation_module.cpp @@ -18,6 +18,8 @@ #include +#include + namespace autoware::imu_corrector { class GyroBiasEstimationModuleTest : public ::testing::Test diff --git a/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp index 26be762acca43..5021a3551c939 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp @@ -18,6 +18,8 @@ #include #include +#include +#include namespace autoware::pointcloud_preprocessor { diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index a67c9f7f018e1..f8baae3405873 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -58,6 +58,7 @@ #include #include +#include #include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp index c1b3605c8b97c..ecbc5b8fd13ef 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/crop_box_filter/crop_box_filter_node.cpp @@ -53,6 +53,7 @@ #include +#include #include namespace autoware::pointcloud_preprocessor diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp index 43a44f836b61a..8391894a4ada6 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp @@ -20,6 +20,10 @@ #include #include +#include +#include +#include + namespace autoware::pointcloud_preprocessor { diff --git a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp index 896c7fe563e64..9eaafeae9dbc7 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/distortion_corrector/distortion_corrector_node.cpp @@ -16,6 +16,10 @@ #include "autoware/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp" +#include +#include +#include + namespace autoware::pointcloud_preprocessor { /** @brief Constructor. */ diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp index 9a01ba3ddc1b1..804a91591271d 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/faster_voxel_grid_downsample_filter.cpp @@ -15,6 +15,7 @@ #include "autoware/pointcloud_preprocessor/downsample_filter/faster_voxel_grid_downsample_filter.hpp" #include +#include namespace autoware::pointcloud_preprocessor { diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp index e3c6af7433dda..10e2fa2511478 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp @@ -16,6 +16,9 @@ #include "robin_hood.h" +#include +#include + namespace { /** diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h index dd5cc9d60dd76..55307a2aa5552 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/robin_hood.h @@ -68,6 +68,7 @@ #include #include #include +#include #if __cplusplus >= 201703L #include #endif @@ -85,7 +86,7 @@ #ifdef ROBIN_HOOD_TRACE_ENABLED #include #define ROBIN_HOOD_TRACE(...) \ - std::cout << __FUNCTION__ << "@" << __LINE__ << ": " << __VA_ARGS__ << std::endl; + std::cout << __FUNCTION__ << "@" << __LINE__ << ": " << __VA_ARGS__ << std::endl; // NOLINT #else #define ROBIN_HOOD_TRACE(x) #endif diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp index 59000d71b8ad6..fae9043143ba4 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp @@ -19,6 +19,8 @@ #include #include +#include +#include #include namespace autoware::pointcloud_preprocessor { diff --git a/sensing/autoware_pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp b/sensing/autoware_pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp index 71b4c2026396e..e4bac9e35c248 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/polygon_remover/polygon_remover.cpp @@ -14,6 +14,8 @@ #include "autoware/pointcloud_preprocessor/polygon_remover/polygon_remover.hpp" +#include + namespace autoware::pointcloud_preprocessor { PolygonRemoverComponent::PolygonRemoverComponent(const rclcpp::NodeOptions & options) diff --git a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp index 5bf5069f1200f..42170fd88ee36 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp @@ -28,6 +28,7 @@ #include #include +#include #include #include #include diff --git a/sensing/autoware_pointcloud_preprocessor/src/utility/geometry.cpp b/sensing/autoware_pointcloud_preprocessor/src/utility/geometry.cpp index 7e9604c3dd305..1d08df944ca18 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/utility/geometry.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/utility/geometry.cpp @@ -14,6 +14,8 @@ #include "autoware/pointcloud_preprocessor/utility/geometry.hpp" +#include + namespace autoware::pointcloud_preprocessor::utils { void to_cgal_polygon(const geometry_msgs::msg::Polygon & polygon_in, PolygonCgal & polygon_out) diff --git a/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter_node.cpp index 6fdf7791601cf..310b86526193c 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/vector_map_inside_area_filter_node.cpp @@ -14,6 +14,10 @@ #include "autoware/pointcloud_preprocessor/vector_map_filter/vector_map_inside_area_filter_node.hpp" +#include +#include +#include + namespace { autoware::universe_utils::Box2d calcBoundingBox( diff --git a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp index 895061229a994..aba3c354473eb 100644 --- a/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/test/test_distortion_corrector_node.cpp @@ -41,6 +41,10 @@ #include #include +#include +#include +#include +#include enum AngleCoordinateSystem { HESAI, VELODYNE, CARTESIAN }; class DistortionCorrectorTest : public ::testing::Test diff --git a/sensing/autoware_radar_tracks_noise_filter/test/radar_tracks_noise_filter/test_radar_tracks_noise_filter_is_noise.cpp b/sensing/autoware_radar_tracks_noise_filter/test/radar_tracks_noise_filter/test_radar_tracks_noise_filter_is_noise.cpp index ea2dfc28b5a4c..e8551ae922f19 100644 --- a/sensing/autoware_radar_tracks_noise_filter/test/radar_tracks_noise_filter/test_radar_tracks_noise_filter_is_noise.cpp +++ b/sensing/autoware_radar_tracks_noise_filter/test/radar_tracks_noise_filter/test_radar_tracks_noise_filter_is_noise.cpp @@ -18,6 +18,8 @@ #include +#include + std::shared_ptr get_node( float velocity_y_threshold) { diff --git a/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp b/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp index c382f0f16f6e5..ab9787fb6020d 100644 --- a/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp +++ b/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp @@ -14,6 +14,8 @@ #include "vehicle_velocity_converter/vehicle_velocity_converter.hpp" +#include + VehicleVelocityConverter::VehicleVelocityConverter(const rclcpp::NodeOptions & options) : rclcpp::Node("vehicle_velocity_converter", options) { From 105ab6f4c934843ed8d01d7df39c5b0986d73c2a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:14:56 +0300 Subject: [PATCH 228/273] fix(cpplint): include what you use - simulator (#9572) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- simulator/dummy_perception_publisher/src/node.cpp | 2 ++ .../dummy_perception_publisher/src/pointcloud_creator.cpp | 1 + .../src/signed_distance_function.cpp | 1 + .../include/fault_injection/fault_injection_diag_updater.hpp | 1 + .../src/interconnected_model.cpp | 4 ++++ .../src/model_connections_helpers.cpp | 2 ++ .../learning_based_vehicle_model/src/simple_pymodel.cpp | 1 + .../simple_planning_simulator_core.cpp | 2 ++ .../src/simple_planning_simulator/utils/csv_loader.cpp | 2 ++ .../vehicle_model/sim_model_actuation_cmd.cpp | 2 ++ .../vehicle_model/sim_model_delay_steer_map_acc_geared.cpp | 1 + .../vehicle_model/sim_model_learned_steer_vel.cpp | 3 +++ .../test/test_simple_planning_simulator.cpp | 5 +++++ .../src/tools/interactive_object.cpp | 1 + 14 files changed, 28 insertions(+) diff --git a/simulator/dummy_perception_publisher/src/node.cpp b/simulator/dummy_perception_publisher/src/node.cpp index dba230f23f108..d72b16d303cec 100644 --- a/simulator/dummy_perception_publisher/src/node.cpp +++ b/simulator/dummy_perception_publisher/src/node.cpp @@ -20,6 +20,8 @@ #include #include #include + +#include #ifdef ROS_DISTRO_GALACTIC #include #else diff --git a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp b/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp index 05354fa0a9663..977336f63eee3 100644 --- a/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp +++ b/simulator/dummy_perception_publisher/src/pointcloud_creator.cpp @@ -24,6 +24,7 @@ #include #include #include +#include namespace { diff --git a/simulator/dummy_perception_publisher/src/signed_distance_function.cpp b/simulator/dummy_perception_publisher/src/signed_distance_function.cpp index e20c19da93af0..01bef1851b25e 100644 --- a/simulator/dummy_perception_publisher/src/signed_distance_function.cpp +++ b/simulator/dummy_perception_publisher/src/signed_distance_function.cpp @@ -16,6 +16,7 @@ #include +#include #include #include diff --git a/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp b/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp index 948c2b45f6615..0a71c1681d1d3 100644 --- a/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp +++ b/simulator/fault_injection/include/fault_injection/fault_injection_diag_updater.hpp @@ -51,6 +51,7 @@ #include +#include #include #include #include diff --git a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp b/simulator/learning_based_vehicle_model/src/interconnected_model.cpp index 4dd3b321312d0..d2fef15aa4e88 100644 --- a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp +++ b/simulator/learning_based_vehicle_model/src/interconnected_model.cpp @@ -14,6 +14,10 @@ #include "learning_based_vehicle_model/interconnected_model.hpp" +#include +#include +#include + void InterconnectedModel::mapInputs(std::vector in_names) { // index in "map_in_to_sig_vec" is index in "in_names" and value in "map_in_to_sig_vec" is index diff --git a/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp b/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp index c7944116d1758..b300f3837b18a 100644 --- a/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp +++ b/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp @@ -14,6 +14,8 @@ #include "learning_based_vehicle_model/model_connections_helpers.hpp" +#include + std::vector fillVectorUsingMap( std::vector vector1, std::vector vector2, const std::vector & map, bool inverse) diff --git a/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp b/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp index 9c3cb9aa06150..10581179baf4a 100644 --- a/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp +++ b/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace py = pybind11; diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 685708844d32d..d61654c32af02 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -35,9 +35,11 @@ #include #include #include +#include #include #include #include +#include using namespace std::literals::chrono_literals; diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp index b410f089725a2..fa1f7978a798c 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp @@ -15,8 +15,10 @@ #include "simple_planning_simulator/utils/csv_loader.hpp" #include +#include #include #include +#include #include CSVLoader::CSVLoader(const std::string & csv_path) diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp index 469c30dc4f0cf..bfcf571d8c09b 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp @@ -17,6 +17,8 @@ #include "autoware_vehicle_msgs/msg/gear_command.hpp" #include +#include +#include bool ActuationMap::readActuationMapFromCSV(const std::string & csv_path, const bool validation) { diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp index b987f74db0436..ffef5ab7b236c 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp @@ -17,6 +17,7 @@ #include "autoware_vehicle_msgs/msg/gear_command.hpp" #include +#include SimModelDelaySteerMapAccGeared::SimModelDelaySteerMapAccGeared( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp index fba34e04ade7c..4ddcc0e498b70 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp @@ -17,6 +17,9 @@ #include "learning_based_vehicle_model/interconnected_model.hpp" #include +#include +#include +#include SimModelLearnedSteerVel::SimModelLearnedSteerVel( double dt, std::vector model_python_paths, diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index 6f2590417e574..0baa3302f86c7 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -19,6 +19,11 @@ #include "tier4_vehicle_msgs/msg/actuation_command_stamped.hpp" +#include +#include +#include +#include + #ifdef ROS_DISTRO_GALACTIC #include "tf2_geometry_msgs/tf2_geometry_msgs.h" #else diff --git a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp index 83852d0c85011..1daff9459f447 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp +++ b/simulator/tier4_dummy_object_rviz_plugin/src/tools/interactive_object.cpp @@ -55,6 +55,7 @@ #include #include #include +#include namespace rviz_plugins { From ff45f026558de1e45945318f7782e68f82297b74 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:15:08 +0300 Subject: [PATCH 229/273] fix(cpplint): include what you use - system (#9573) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- system/autoware_default_adapi/src/perception.cpp | 1 + system/autoware_default_adapi/src/vehicle.cpp | 1 + system/bluetooth_monitor/service/l2ping_service.cpp | 1 + system/bluetooth_monitor/service/main.cpp | 2 ++ system/component_state_monitor/src/main.cpp | 2 ++ .../diagnostic_graph_aggregator/src/common/graph/config.cpp | 2 ++ system/diagnostic_graph_aggregator/src/common/graph/data.cpp | 2 ++ .../diagnostic_graph_aggregator/src/common/graph/error.cpp | 2 ++ .../diagnostic_graph_aggregator/src/common/graph/graph.cpp | 1 + .../diagnostic_graph_aggregator/src/common/graph/loader.cpp | 4 ++++ system/diagnostic_graph_aggregator/src/tool/plantuml.cpp | 1 + system/diagnostic_graph_aggregator/src/tool/tree.cpp | 1 + system/diagnostic_graph_aggregator/test/src/test2.cpp | 3 +++ system/diagnostic_graph_aggregator/test/src/utils.cpp | 2 ++ system/diagnostic_graph_utils/src/lib/graph.cpp | 2 ++ system/diagnostic_graph_utils/src/lib/subscription.cpp | 2 ++ system/diagnostic_graph_utils/src/node/dump.cpp | 1 + system/diagnostic_graph_utils/src/node/logging.cpp | 1 + .../dummy_diag_publisher/src/dummy_diag_publisher_core.cpp | 5 +++++ .../src/duplicated_node_checker_core.cpp | 1 + system/hazard_status_converter/src/converter.cpp | 1 + .../mrm_comfortable_stop_operator_core.cpp | 2 ++ .../mrm_emergency_stop_operator_core.cpp | 2 ++ system/system_monitor/reader/msr_reader/msr_reader.cpp | 1 + .../reader/traffic_reader/traffic_reader_main.cpp | 2 ++ .../reader/traffic_reader/traffic_reader_service.cpp | 5 +++++ system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp | 2 ++ system/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp | 1 + system/system_monitor/src/hdd_monitor/hdd_monitor.cpp | 2 ++ system/system_monitor/src/mem_monitor/mem_monitor.cpp | 1 + system/system_monitor/src/net_monitor/net_monitor.cpp | 5 +++++ system/system_monitor/src/ntp_monitor/ntp_monitor.cpp | 1 + .../system_monitor/src/process_monitor/process_monitor.cpp | 1 + .../system_monitor/src/voltage_monitor/voltage_monitor.cpp | 1 + system/system_monitor/test/src/process_monitor/top3.cpp | 2 ++ 35 files changed, 66 insertions(+) diff --git a/system/autoware_default_adapi/src/perception.cpp b/system/autoware_default_adapi/src/perception.cpp index e764af4ca816a..3e858e7763baf 100644 --- a/system/autoware_default_adapi/src/perception.cpp +++ b/system/autoware_default_adapi/src/perception.cpp @@ -14,6 +14,7 @@ #include "perception.hpp" +#include #include namespace autoware::default_adapi diff --git a/system/autoware_default_adapi/src/vehicle.cpp b/system/autoware_default_adapi/src/vehicle.cpp index 5620062ede278..fc35efff523c2 100644 --- a/system/autoware_default_adapi/src/vehicle.cpp +++ b/system/autoware_default_adapi/src/vehicle.cpp @@ -20,6 +20,7 @@ #include #include +#include namespace autoware::default_adapi { diff --git a/system/bluetooth_monitor/service/l2ping_service.cpp b/system/bluetooth_monitor/service/l2ping_service.cpp index f20c763d643ce..827a7e3060acc 100644 --- a/system/bluetooth_monitor/service/l2ping_service.cpp +++ b/system/bluetooth_monitor/service/l2ping_service.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #define FMT_HEADER_ONLY #include diff --git a/system/bluetooth_monitor/service/main.cpp b/system/bluetooth_monitor/service/main.cpp index a3ccb971a5eb7..d3aef2c0696dd 100644 --- a/system/bluetooth_monitor/service/main.cpp +++ b/system/bluetooth_monitor/service/main.cpp @@ -20,6 +20,8 @@ #include #include +#include + /** * @brief print usage */ diff --git a/system/component_state_monitor/src/main.cpp b/system/component_state_monitor/src/main.cpp index 2a05ef1a38911..c87963b1b21c0 100644 --- a/system/component_state_monitor/src/main.cpp +++ b/system/component_state_monitor/src/main.cpp @@ -14,6 +14,8 @@ #include "main.hpp" +#include +#include #include namespace component_state_monitor diff --git a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp index b91b777831368..e622d089109f4 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/config.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/config.cpp @@ -23,9 +23,11 @@ #include #include #include +#include #include #include #include +#include namespace diagnostic_graph_aggregator { diff --git a/system/diagnostic_graph_aggregator/src/common/graph/data.cpp b/system/diagnostic_graph_aggregator/src/common/graph/data.cpp index 2a4aef7e39c1f..e1d053e6d259c 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/data.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/data.cpp @@ -14,6 +14,8 @@ #include "data.hpp" +#include + namespace diagnostic_graph_aggregator { diff --git a/system/diagnostic_graph_aggregator/src/common/graph/error.cpp b/system/diagnostic_graph_aggregator/src/common/graph/error.cpp index e78a444c5ab7f..7a4336e62d8a3 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/error.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/error.cpp @@ -14,6 +14,8 @@ #include "error.hpp" +#include + namespace diagnostic_graph_aggregator { diff --git a/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp index 0a7d78a5ce982..7977209b4905c 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/graph.cpp @@ -19,6 +19,7 @@ #include "loader.hpp" #include "units.hpp" +#include #include namespace diagnostic_graph_aggregator diff --git a/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp b/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp index e4d2e470a0d32..5edef61340fe8 100644 --- a/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp +++ b/system/diagnostic_graph_aggregator/src/common/graph/loader.cpp @@ -20,7 +20,11 @@ #include "types.hpp" #include "units.hpp" +#include +#include +#include #include +#include namespace diagnostic_graph_aggregator { diff --git a/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp b/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp index 9f7eb34bf3454..68c0082908430 100644 --- a/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp +++ b/system/diagnostic_graph_aggregator/src/tool/plantuml.cpp @@ -16,6 +16,7 @@ #include "graph/units.hpp" #include +#include namespace diagnostic_graph_aggregator { diff --git a/system/diagnostic_graph_aggregator/src/tool/tree.cpp b/system/diagnostic_graph_aggregator/src/tool/tree.cpp index 1e6fe93b18a80..f367ec2113808 100644 --- a/system/diagnostic_graph_aggregator/src/tool/tree.cpp +++ b/system/diagnostic_graph_aggregator/src/tool/tree.cpp @@ -16,6 +16,7 @@ #include "graph/units.hpp" #include +#include namespace diagnostic_graph_aggregator { diff --git a/system/diagnostic_graph_aggregator/test/src/test2.cpp b/system/diagnostic_graph_aggregator/test/src/test2.cpp index b010994f5a1ca..4a0199a89f37e 100644 --- a/system/diagnostic_graph_aggregator/test/src/test2.cpp +++ b/system/diagnostic_graph_aggregator/test/src/test2.cpp @@ -22,6 +22,9 @@ #include +#include +#include + using namespace diagnostic_graph_aggregator; // NOLINT(build/namespaces) using diagnostic_msgs::msg::DiagnosticArray; diff --git a/system/diagnostic_graph_aggregator/test/src/utils.cpp b/system/diagnostic_graph_aggregator/test/src/utils.cpp index c64812afa649a..f92a414e2a678 100644 --- a/system/diagnostic_graph_aggregator/test/src/utils.cpp +++ b/system/diagnostic_graph_aggregator/test/src/utils.cpp @@ -14,6 +14,8 @@ #include "utils.hpp" +#include + std::filesystem::path resource(const std::string & path) { return std::filesystem::path(TEST_RESOURCE_PATH) / path; diff --git a/system/diagnostic_graph_utils/src/lib/graph.cpp b/system/diagnostic_graph_utils/src/lib/graph.cpp index 423e1b40be12e..007b42547bee1 100644 --- a/system/diagnostic_graph_utils/src/lib/graph.cpp +++ b/system/diagnostic_graph_utils/src/lib/graph.cpp @@ -14,6 +14,8 @@ #include "diagnostic_graph_utils/graph.hpp" +#include + namespace diagnostic_graph_utils { diff --git a/system/diagnostic_graph_utils/src/lib/subscription.cpp b/system/diagnostic_graph_utils/src/lib/subscription.cpp index 655544c2e1f28..c10481ef8f16e 100644 --- a/system/diagnostic_graph_utils/src/lib/subscription.cpp +++ b/system/diagnostic_graph_utils/src/lib/subscription.cpp @@ -14,6 +14,8 @@ #include "diagnostic_graph_utils/subscription.hpp" +#include + namespace diagnostic_graph_utils { diff --git a/system/diagnostic_graph_utils/src/node/dump.cpp b/system/diagnostic_graph_utils/src/node/dump.cpp index 8456a92cbaa9b..42c66224b2c37 100644 --- a/system/diagnostic_graph_utils/src/node/dump.cpp +++ b/system/diagnostic_graph_utils/src/node/dump.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include namespace diagnostic_graph_utils diff --git a/system/diagnostic_graph_utils/src/node/logging.cpp b/system/diagnostic_graph_utils/src/node/logging.cpp index 009af51e949cd..b166a087200a0 100644 --- a/system/diagnostic_graph_utils/src/node/logging.cpp +++ b/system/diagnostic_graph_utils/src/node/logging.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include namespace diagnostic_graph_utils diff --git a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp index 51a0846b45179..6bc1378507a37 100644 --- a/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp +++ b/system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp @@ -14,6 +14,11 @@ #include "dummy_diag_publisher/dummy_diag_publisher_core.hpp" +#include +#include +#include +#include + #define FMT_HEADER_ONLY #include diff --git a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp b/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp index 5c698a0a01860..1bc14bf927835 100644 --- a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp +++ b/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include diff --git a/system/hazard_status_converter/src/converter.cpp b/system/hazard_status_converter/src/converter.cpp index d92af2186f415..52cfef93aa522 100644 --- a/system/hazard_status_converter/src/converter.cpp +++ b/system/hazard_status_converter/src/converter.cpp @@ -14,6 +14,7 @@ #include "converter.hpp" +#include #include #include diff --git a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp b/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp index 6b18555053582..fc703ab16e259 100644 --- a/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp +++ b/system/mrm_comfortable_stop_operator/src/mrm_comfortable_stop_operator/mrm_comfortable_stop_operator_core.cpp @@ -16,6 +16,8 @@ #include +#include + namespace mrm_comfortable_stop_operator { diff --git a/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp b/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp index 5c1ca5e04de0e..9c941888a3545 100644 --- a/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp +++ b/system/mrm_emergency_stop_operator/src/mrm_emergency_stop_operator/mrm_emergency_stop_operator_core.cpp @@ -16,6 +16,8 @@ #include +#include + namespace mrm_emergency_stop_operator { diff --git a/system/system_monitor/reader/msr_reader/msr_reader.cpp b/system/system_monitor/reader/msr_reader/msr_reader.cpp index 59a6edc91ace7..fc7bcab795be0 100644 --- a/system/system_monitor/reader/msr_reader/msr_reader.cpp +++ b/system/system_monitor/reader/msr_reader/msr_reader.cpp @@ -35,6 +35,7 @@ #include #include +#include #include #include #include diff --git a/system/system_monitor/reader/traffic_reader/traffic_reader_main.cpp b/system/system_monitor/reader/traffic_reader/traffic_reader_main.cpp index 940afdd9e5c35..cc0a8f81b6bff 100644 --- a/system/system_monitor/reader/traffic_reader/traffic_reader_main.cpp +++ b/system/system_monitor/reader/traffic_reader/traffic_reader_main.cpp @@ -18,7 +18,9 @@ #include #include +#include #include +#include /** * @brief print usage diff --git a/system/system_monitor/reader/traffic_reader/traffic_reader_service.cpp b/system/system_monitor/reader/traffic_reader/traffic_reader_service.cpp index 927f1b175b46b..fe5df51946fc6 100644 --- a/system/system_monitor/reader/traffic_reader/traffic_reader_service.cpp +++ b/system/system_monitor/reader/traffic_reader/traffic_reader_service.cpp @@ -26,6 +26,11 @@ #include #include +#include +#include +#include +#include + namespace process = boost::process; namespace traffic_reader_service diff --git a/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp b/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp index 13d7151bb14c7..f824ad49df867 100644 --- a/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp +++ b/system/system_monitor/src/cpu_monitor/cpu_monitor_base.cpp @@ -30,8 +30,10 @@ #include #include +#include #include #include +#include namespace bp = boost::process; namespace fs = boost::filesystem; diff --git a/system/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp b/system/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp index 0000d6ead1c6a..496a782add33e 100644 --- a/system/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp +++ b/system/system_monitor/src/gpu_monitor/nvml_gpu_monitor.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include diff --git a/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp b/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp index 50ac4363da609..60e1c401a05f3 100644 --- a/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp +++ b/system/system_monitor/src/hdd_monitor/hdd_monitor.cpp @@ -32,8 +32,10 @@ #include #include +#include #include #include +#include #include namespace bp = boost::process; diff --git a/system/system_monitor/src/mem_monitor/mem_monitor.cpp b/system/system_monitor/src/mem_monitor/mem_monitor.cpp index 4d141294c3fa5..1caa011e15bed 100644 --- a/system/system_monitor/src/mem_monitor/mem_monitor.cpp +++ b/system/system_monitor/src/mem_monitor/mem_monitor.cpp @@ -26,6 +26,7 @@ #include #include +#include #include namespace bp = boost::process; diff --git a/system/system_monitor/src/net_monitor/net_monitor.cpp b/system/system_monitor/src/net_monitor/net_monitor.cpp index a074663a7ee7c..d99150f0b3037 100644 --- a/system/system_monitor/src/net_monitor/net_monitor.cpp +++ b/system/system_monitor/src/net_monitor/net_monitor.cpp @@ -26,6 +26,11 @@ #include #include +#include +#include +#include +#include + #define FMT_HEADER_ONLY #include #include diff --git a/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp b/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp index 4e697fa18ec50..590793cf1f7fe 100644 --- a/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp +++ b/system/system_monitor/src/ntp_monitor/ntp_monitor.cpp @@ -29,6 +29,7 @@ #include #include #include +#include namespace bp = boost::process; namespace fs = boost::filesystem; diff --git a/system/system_monitor/src/process_monitor/process_monitor.cpp b/system/system_monitor/src/process_monitor/process_monitor.cpp index 73059d2d162fa..faaf1abf1c9d3 100644 --- a/system/system_monitor/src/process_monitor/process_monitor.cpp +++ b/system/system_monitor/src/process_monitor/process_monitor.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include ProcessMonitor::ProcessMonitor(const rclcpp::NodeOptions & options) diff --git a/system/system_monitor/src/voltage_monitor/voltage_monitor.cpp b/system/system_monitor/src/voltage_monitor/voltage_monitor.cpp index fda75c21535cf..f7771fb9f47d3 100644 --- a/system/system_monitor/src/voltage_monitor/voltage_monitor.cpp +++ b/system/system_monitor/src/voltage_monitor/voltage_monitor.cpp @@ -34,6 +34,7 @@ #include #include #include +#include #include namespace bp = boost::process; diff --git a/system/system_monitor/test/src/process_monitor/top3.cpp b/system/system_monitor/test/src/process_monitor/top3.cpp index 2725ee2676064..3400b608ed9b7 100644 --- a/system/system_monitor/test/src/process_monitor/top3.cpp +++ b/system/system_monitor/test/src/process_monitor/top3.cpp @@ -19,6 +19,8 @@ #include +#include + int main(int argc, char ** argv) { printf("Tasks:"); From b54210d138536ec86045c5e602947ee2a2257602 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:15:21 +0300 Subject: [PATCH 230/273] fix(cpplint): include what you use - tools (#9574) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- tools/reaction_analyzer/src/reaction_analyzer_node.cpp | 2 ++ tools/reaction_analyzer/src/subscriber.cpp | 3 +++ tools/reaction_analyzer/src/topic_publisher.cpp | 4 ++++ tools/reaction_analyzer/src/utils.cpp | 6 ++++++ 4 files changed, 15 insertions(+) diff --git a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp index e890a5208bf22..02743537d6bb3 100644 --- a/tools/reaction_analyzer/src/reaction_analyzer_node.cpp +++ b/tools/reaction_analyzer/src/reaction_analyzer_node.cpp @@ -15,7 +15,9 @@ #include "reaction_analyzer_node.hpp" #include +#include #include +#include namespace reaction_analyzer { diff --git a/tools/reaction_analyzer/src/subscriber.cpp b/tools/reaction_analyzer/src/subscriber.cpp index a5d1be613ee5a..0e119c3fdcbf7 100644 --- a/tools/reaction_analyzer/src/subscriber.cpp +++ b/tools/reaction_analyzer/src/subscriber.cpp @@ -15,8 +15,11 @@ #include "subscriber.hpp" #include +#include #include +#include #include +#include namespace reaction_analyzer::subscriber { diff --git a/tools/reaction_analyzer/src/topic_publisher.cpp b/tools/reaction_analyzer/src/topic_publisher.cpp index f720786d422bc..c78faf7ad656e 100644 --- a/tools/reaction_analyzer/src/topic_publisher.cpp +++ b/tools/reaction_analyzer/src/topic_publisher.cpp @@ -15,7 +15,11 @@ #include "topic_publisher.hpp" #include +#include #include +#include +#include +#include namespace reaction_analyzer::topic_publisher { diff --git a/tools/reaction_analyzer/src/utils.cpp b/tools/reaction_analyzer/src/utils.cpp index 107c1deb2f196..9075cdc4a77dd 100644 --- a/tools/reaction_analyzer/src/utils.cpp +++ b/tools/reaction_analyzer/src/utils.cpp @@ -14,6 +14,12 @@ #include "utils.hpp" +#include +#include +#include +#include +#include + namespace reaction_analyzer { SubscriberMessageType get_subscriber_message_type(const std::string & message_type) From 065b603bb05efc7484184805a330d89858183507 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:15:35 +0300 Subject: [PATCH 231/273] fix(cpplint): include what you use - vehicle (#9575) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../accel_brake_map_calibrator_node.hpp | 1 + .../src/accel_brake_map_calibrator_node.cpp | 1 + vehicle/autoware_external_cmd_converter/src/node.cpp | 1 + .../tests/test_external_cmd_converter.cpp | 1 + vehicle/autoware_raw_vehicle_cmd_converter/src/csv_loader.cpp | 2 ++ vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp | 1 + vehicle/autoware_raw_vehicle_cmd_converter/src/pid.cpp | 1 + .../test/test_autoware_raw_vehicle_cmd_converter.cpp | 1 + 8 files changed, 9 insertions(+) diff --git a/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp b/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp index 39d81c26961bb..2a0ad4f987dad 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp +++ b/vehicle/autoware_accel_brake_map_calibrator/include/autoware_accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp @@ -47,6 +47,7 @@ #include "tier4_vehicle_msgs/srv/update_accel_brake_map.hpp" #include "visualization_msgs/msg/marker_array.hpp" +#include #include #include #include diff --git a/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp b/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp index 3750fdb77b258..9d7de55aff54d 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp +++ b/vehicle/autoware_accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp @@ -19,6 +19,7 @@ #include "rclcpp/logging.hpp" #include +#include #include #include #include diff --git a/vehicle/autoware_external_cmd_converter/src/node.cpp b/vehicle/autoware_external_cmd_converter/src/node.cpp index 0f7166c71fbff..267836b91f945 100644 --- a/vehicle/autoware_external_cmd_converter/src/node.cpp +++ b/vehicle/autoware_external_cmd_converter/src/node.cpp @@ -16,6 +16,7 @@ #include #include +#include #include #include #include diff --git a/vehicle/autoware_external_cmd_converter/tests/test_external_cmd_converter.cpp b/vehicle/autoware_external_cmd_converter/tests/test_external_cmd_converter.cpp index a508359af60e8..1fc037592bb08 100644 --- a/vehicle/autoware_external_cmd_converter/tests/test_external_cmd_converter.cpp +++ b/vehicle/autoware_external_cmd_converter/tests/test_external_cmd_converter.cpp @@ -24,6 +24,7 @@ #include #include +#include using autoware::external_cmd_converter::ExternalCmdConverterNode; using nav_msgs::msg::Odometry; using tier4_control_msgs::msg::GateMode; diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/csv_loader.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/csv_loader.cpp index 0a31e2089e4ef..999b52e1a1c81 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/csv_loader.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/csv_loader.cpp @@ -15,7 +15,9 @@ #include "autoware_raw_vehicle_cmd_converter/csv_loader.hpp" #include +#include #include +#include #include namespace autoware::raw_vehicle_cmd_converter diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp index 362fb53eba67d..e4cdbe60fd4cd 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp @@ -15,6 +15,7 @@ #include "autoware_raw_vehicle_cmd_converter/node.hpp" #include +#include #include #include #include diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/pid.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/pid.cpp index 6b2bffa7630f9..d41f4facf1aef 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/pid.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/pid.cpp @@ -17,6 +17,7 @@ #include #include +#include #include namespace autoware::raw_vehicle_cmd_converter diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp index 0d716eef3369b..698e1f8562ee7 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/test/test_autoware_raw_vehicle_cmd_converter.cpp @@ -21,6 +21,7 @@ #include "gtest/gtest.h" #include +#include /* * Throttle data: (vel, throttle -> acc) From 15944873a6dd0f0eb1de561191e7560c750f41f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Wed, 4 Dec 2024 21:15:49 +0300 Subject: [PATCH 232/273] fix(cpplint): include what you use - visualization (#9576) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- visualization/autoware_pyplot/src/axes.cpp | 2 ++ visualization/autoware_pyplot/src/common.cpp | 2 ++ visualization/autoware_pyplot/src/pyplot.cpp | 3 +++ 3 files changed, 7 insertions(+) diff --git a/visualization/autoware_pyplot/src/axes.cpp b/visualization/autoware_pyplot/src/axes.cpp index 0f08ffe5773f6..95f871ea6179f 100644 --- a/visualization/autoware_pyplot/src/axes.cpp +++ b/visualization/autoware_pyplot/src/axes.cpp @@ -15,6 +15,8 @@ #include #include +#include + namespace autoware::pyplot { inline namespace axes diff --git a/visualization/autoware_pyplot/src/common.cpp b/visualization/autoware_pyplot/src/common.cpp index 5b3fffa37f30e..5f1226cb5bae1 100644 --- a/visualization/autoware_pyplot/src/common.cpp +++ b/visualization/autoware_pyplot/src/common.cpp @@ -14,6 +14,8 @@ #include +#include + namespace autoware::pyplot { inline namespace common diff --git a/visualization/autoware_pyplot/src/pyplot.cpp b/visualization/autoware_pyplot/src/pyplot.cpp index d45d34a35d767..624a1b1db07df 100644 --- a/visualization/autoware_pyplot/src/pyplot.cpp +++ b/visualization/autoware_pyplot/src/pyplot.cpp @@ -15,6 +15,9 @@ #include #include +#include +#include + namespace autoware::pyplot { PyPlot::PyPlot(const pybind11::module & mod_) : mod(mod_) From 87e95bf00a6ed23162d652fe38c97695f3ed5bd8 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 5 Dec 2024 08:13:07 +0900 Subject: [PATCH 233/273] feat(lane_changing): improve computation of lane changing acceleration (#9545) * allow decelerating in lane changing phase near terminal Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * run pre-commit check Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * fix format Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../README.md | 1 + .../config/lane_change.param.yaml | 1 + .../utils/calculation.hpp | 5 +++-- .../utils/parameters.hpp | 1 + .../src/manager.cpp | 4 ++++ .../src/utils/calculation.cpp | 14 ++++++++++---- 6 files changed, 20 insertions(+), 6 deletions(-) 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 d24a89bf03000..499327e3b8483 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 @@ -893,6 +893,7 @@ The following parameters are configurable in [lane_change.param.yaml](https://gi | `trajectory.lat_acc_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by lateral acceleration | 3 | | `trajectory.max_longitudinal_acc` | [m/s2] | double | maximum longitudinal acceleration for lane change | 1.0 | | `trajectory.min_longitudinal_acc` | [m/s2] | double | maximum longitudinal deceleration for lane change | -1.0 | +| `trajectory.lane_changing_decel_factor` | [-] | double | longitudinal deceleration factor during lane changing phase | 0.5 | | `min_length_for_turn_signal_activation` | [m] | double | Turn signal will be activated if the ego vehicle approaches to this length from minimum lane change length | 10.0 | | `lateral_acceleration.velocity` | [m/s] | double | Reference velocity for lateral acceleration calculation (look up table) | [0.0, 4.0, 10.0] | | `lateral_acceleration.min_values` | [m/s2] | double | Min lateral acceleration values corresponding to velocity (look up table) | [0.4, 0.4, 0.4] | 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 6baf05edad484..572caedb58306 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 @@ -20,6 +20,7 @@ min_lane_changing_velocity: 2.78 lon_acc_sampling_num: 5 lat_acc_sampling_num: 3 + lane_changing_decel_factor: 0.5 # delay lane change delay_lane_change: 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 index b6e6cb968ace8..b2aa21e4dc085 100644 --- 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 @@ -106,8 +106,9 @@ double calc_ego_dist_to_lanes_start( const lanelet::ConstLanelets & target_lanes); double calc_lane_changing_acceleration( - const double initial_lane_changing_velocity, const double max_path_velocity, - const double lane_changing_time, const double prepare_longitudinal_acc); + const CommonDataPtr & common_data_ptr, const double initial_lane_changing_velocity, + const double max_path_velocity, const double lane_changing_time, + const double prepare_longitudinal_acc); /** * @brief Calculates the distance required during a lane change operation. diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp index 7f97eb872f795..31bd5d94f09c8 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp @@ -122,6 +122,7 @@ struct TrajectoryParameters double th_prepare_length_diff{0.5}; double th_lane_changing_length_diff{0.5}; double min_lane_changing_velocity{5.6}; + double lane_changing_decel_factor{0.5}; int lon_acc_sampling_num{10}; int lat_acc_sampling_num{10}; LateralAccelerationMap lat_acc_map{}; 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 b193ce33b17fa..baba4311e2175 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 @@ -59,6 +59,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("trajectory.th_lane_changing_length_diff")); p.trajectory.min_lane_changing_velocity = getOrDeclareParameter(*node, parameter("trajectory.min_lane_changing_velocity")); + p.trajectory.lane_changing_decel_factor = + getOrDeclareParameter(*node, parameter("trajectory.lane_changing_decel_factor")); p.trajectory.lon_acc_sampling_num = getOrDeclareParameter(*node, parameter("trajectory.lon_acc_sampling_num")); p.trajectory.lat_acc_sampling_num = @@ -318,6 +320,8 @@ void LaneChangeModuleManager::updateModuleParams(const std::vectortrajectory.min_longitudinal_acc); updateParam( parameters, ns + "max_longitudinal_acc", p->trajectory.max_longitudinal_acc); + updateParam( + parameters, ns + "lane_changing_decel_factor", p->trajectory.lane_changing_decel_factor); int longitudinal_acc_sampling_num = 0; updateParam(parameters, ns + "lon_acc_sampling_num", longitudinal_acc_sampling_num); if (longitudinal_acc_sampling_num > 0) { 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 index 9cbf9d4beb5ff..68b2debecc4d2 100644 --- 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 @@ -382,11 +382,17 @@ std::vector calc_lon_acceleration_samples( } double calc_lane_changing_acceleration( - const double initial_lane_changing_velocity, const double max_path_velocity, - const double lane_changing_time, const double prepare_longitudinal_acc) + const CommonDataPtr & common_data_ptr, const double initial_lane_changing_velocity, + const double max_path_velocity, const double lane_changing_time, + const double prepare_longitudinal_acc) { if (prepare_longitudinal_acc <= 0.0) { - return 0.0; + const auto & params = common_data_ptr->lc_param_ptr->trajectory; + const auto lane_changing_acc = + common_data_ptr->transient_data.is_ego_near_current_terminal_start + ? prepare_longitudinal_acc * params.lane_changing_decel_factor + : 0.0; + return lane_changing_acc; } return std::clamp( @@ -497,7 +503,7 @@ std::vector calc_shift_phase_metrics( shift_length, common_data_ptr->lc_param_ptr->trajectory.lateral_jerk, lat_acc); const double lane_changing_accel = calc_lane_changing_acceleration( - initial_velocity, max_path_velocity, lane_changing_duration, lon_accel); + common_data_ptr, initial_velocity, max_path_velocity, lane_changing_duration, lon_accel); const auto lane_changing_length = calculation::calc_phase_length( initial_velocity, max_vel, lane_changing_accel, lane_changing_duration); From 0992f1debb6b856b0a2a537fe84e7272a8f0b891 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 5 Dec 2024 09:05:24 +0900 Subject: [PATCH 234/273] feat(lane_change): reduce prepare duration when blinker has been activated (#9185) * add minimum prepare duration parameter Signed-off-by: mohammad alqudah * reduce prepare duration according to signal activation time Signed-off-by: mohammad alqudah * chore: update CODEOWNERS (#9203) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions * refactor(time_utils): prefix package and namespace with autoware (#9173) * refactor(time_utils): prefix package and namespace with autoware Signed-off-by: Esteve Fernandez * refactor(time_utils): prefix package and namespace with autoware Signed-off-by: Esteve Fernandez * style(pre-commit): autofix --------- Signed-off-by: Esteve Fernandez Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(rtc_interface): add requested field (#9202) * add requested feature Signed-off-by: Go Sakayori * Update planning/autoware_rtc_interface/test/test_rtc_interface.cpp Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> --------- Signed-off-by: Go Sakayori Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> * fix(mpc_lateral_controller): correctly resample the MPC trajectory yaws (#9199) Signed-off-by: Maxime CLEMENT * fix(bpp): prevent accessing nullopt (#9204) fix(bpp): calcDistanceToRedTrafficLight null Signed-off-by: Shumpei Wakabayashi * refactor(autoware_map_based_prediction): split pedestrian and bicycle predictor (#9201) * refactor: grouping functions Signed-off-by: Taekjin LEE * refactor: grouping parameters Signed-off-by: Taekjin LEE * refactor: rename member road_users_history to road_users_history_ Signed-off-by: Taekjin LEE * refactor: separate util functions Signed-off-by: Taekjin LEE * refactor: Add predictor_vru.cpp and utils.cpp to map_based_prediction_node Signed-off-by: Taekjin LEE * refactor: Add explicit template instantiation for removeOldObjectsHistory function Signed-off-by: Taekjin LEE * refactor: Add tf2_geometry_msgs to data_structure Signed-off-by: Taekjin LEE * refactor: Remove unused variables and functions in map_based_prediction_node.cpp Signed-off-by: Taekjin LEE * Update perception/autoware_map_based_prediction/include/map_based_prediction/predictor_vru.hpp * Apply suggestions from code review * style(pre-commit): autofix --------- Signed-off-by: Taekjin LEE Co-authored-by: Mamoru Sobue Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (#8912) * Moved ndt_omp into ndt_scan_matcher Signed-off-by: Shintaro Sakoda * Added Copyright Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed include Signed-off-by: Shintaro Sakoda * Fixed cast style Signed-off-by: Shintaro Sakoda * Fixed include Signed-off-by: Shintaro Sakoda * Fixed honorific title Signed-off-by: Shintaro Sakoda * Fixed honorific title Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed include hierarchy Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed include hierarchy Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed hierarchy Signed-off-by: Shintaro Sakoda * Fixed NVTP to NVTL Signed-off-by: Shintaro Sakoda * Added cspell:ignore Signed-off-by: Shintaro Sakoda * Fixed miss spell Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed include Signed-off-by: Shintaro Sakoda * Renamed applyFilter Signed-off-by: Shintaro Sakoda * Moved ***_impl.hpp from include/ to src/ Signed-off-by: Shintaro Sakoda * style(pre-commit): autofix * Fixed variable scope Signed-off-by: Shintaro Sakoda * Fixed to pass by reference Signed-off-by: Shintaro Sakoda --------- Signed-off-by: Shintaro Sakoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * feat(autoware_test_utils): add traffic light msgs parser (#9177) Signed-off-by: Mamoru Sobue * modify implementation to compute and keep actual prepare duration in transient data Signed-off-by: mohammad alqudah * if LC path is approved, set prepare duration in transient data from approved path prepare duration Signed-off-by: mohammad alqudah * change default value of LC param min_prepare_duration Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> * add function to set signal activation time, add docstring for function calc_actual_prepare_duration Signed-off-by: mohammad alqudah * check for zero value max_acc to avoid division by zero Signed-off-by: mohammad alqudah * chore: rename codeowners file Signed-off-by: tomoya.kimura * chore: rename codeowners file Signed-off-by: tomoya.kimura * chore: rename codeowners file Signed-off-by: tomoya.kimura * allow decelerating in lane changing phase near terminal Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * fix units Signed-off-by: mohammad alqudah * allow decelerating in lane changing phase near terminal Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * run pre-commit check Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * fix format Signed-off-by: mohammad alqudah * allow decelerating in lane changing phase near terminal Signed-off-by: mohammad alqudah * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * run pre-commit check Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah * fix format Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Signed-off-by: Esteve Fernandez Signed-off-by: Go Sakayori Signed-off-by: Maxime CLEMENT Signed-off-by: Shumpei Wakabayashi Signed-off-by: Taekjin LEE Signed-off-by: Shintaro Sakoda Signed-off-by: Mamoru Sobue Signed-off-by: tomoya.kimura Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Co-authored-by: github-actions Co-authored-by: Esteve Fernandez <33620+esteve@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Go Sakayori Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Co-authored-by: Taekjin LEE Co-authored-by: Mamoru Sobue Co-authored-by: SakodaShintaro Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Co-authored-by: tomoya.kimura --- .github/{CODEOWNERS => _CODEOWNERS} | 0 .../README.md | 3 +- .../config/lane_change.param.yaml | 3 +- .../scene.hpp | 2 +- .../utils/base_class.hpp | 12 ++++++- .../utils/calculation.hpp | 20 +++++++++++- .../utils/data_structs.hpp | 2 ++ .../utils/parameters.hpp | 3 +- .../src/interface.cpp | 8 ++--- .../src/manager.cpp | 15 ++++++--- .../src/scene.cpp | 27 +++++++++++++--- .../src/utils/calculation.cpp | 31 ++++++++++++++++--- .../test/test_lane_change_scene.cpp | 4 +-- 13 files changed, 104 insertions(+), 26 deletions(-) rename .github/{CODEOWNERS => _CODEOWNERS} (100%) diff --git a/.github/CODEOWNERS b/.github/_CODEOWNERS similarity index 100% rename from .github/CODEOWNERS rename to .github/_CODEOWNERS 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 499327e3b8483..86d8d1c0c1413 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 @@ -886,7 +886,8 @@ 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 | | `backward_length_from_intersection` | [m] | double | Distance threshold from the last intersection to invalidate or cancel the lane change path | 5.0 | -| `trajectory.prepare_duration` | [m] | double | The preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | +| `trajectory.max_prepare_duration` | [s] | double | The maximum preparation time for the ego vehicle to be ready to perform lane change. | 4.0 | +| `trajectory.min_prepare_duration` | [s] | double | The minimum preparation time for the ego vehicle to be ready to perform lane change. | 2.0 | | `trajectory.lateral_jerk` | [m/s3] | double | Lateral jerk value for lane change path generation | 0.5 | | `trajectory.minimum_lane_changing_velocity` | [m/s] | double | Minimum speed during lane changing process. | 2.78 | | `trajectory.lon_acc_sampling_num` | [-] | int | Number of possible lane-changing trajectories that are being influenced by longitudinal acceleration | 3 | 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 572caedb58306..bf892b3058a16 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 @@ -11,7 +11,8 @@ # trajectory generation trajectory: - prepare_duration: 4.0 + max_prepare_duration: 4.0 + min_prepare_duration: 2.0 lateral_jerk: 0.5 min_longitudinal_acc: -1.0 max_longitudinal_acc: 1.0 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 550925c4a10fc..7202a1c6a9108 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 @@ -54,7 +54,7 @@ class NormalLaneChange : public LaneChangeBase void update_lanes(const bool is_approved) final; - void update_transient_data() final; + void update_transient_data(const bool is_approved) final; void update_filtered_objects() final; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp index e5c7fcb6d621e..741b5afb50e08 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/base_class.hpp @@ -68,7 +68,7 @@ class LaneChangeBase virtual void update_lanes(const bool is_approved) = 0; - virtual void update_transient_data() = 0; + virtual void update_transient_data(const bool is_approved) = 0; virtual void update_filtered_objects() = 0; @@ -267,6 +267,15 @@ class LaneChangeBase return turn_signal; } + void set_signal_activation_time(const bool reset = false) const + { + if (reset) { + signal_activation_time_ = std::nullopt; + } else if (!signal_activation_time_) { + signal_activation_time_ = clock_.now(); + } + } + LaneChangeStatus status_{}; PathShifter path_shifter_{}; @@ -292,6 +301,7 @@ class LaneChangeBase mutable StopWatch stop_watch_; mutable lane_change::Debug lane_change_debug_; + mutable std::optional signal_activation_time_{std::nullopt}; rclcpp::Logger logger_ = utils::lane_change::getLogger(getModuleTypeStr()); mutable rclcpp::Clock clock_{RCL_ROS_TIME}; 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 index b2aa21e4dc085..29047c90590b3 100644 --- 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 @@ -75,7 +75,7 @@ double calc_dist_to_last_fit_width( * of the maximum lane change preparation duration and the maximum velocity of the ego vehicle. * * @param common_data_ptr Shared pointer to a CommonData structure, which should include: - * - `lc_param_ptr->lane_change_prepare_duration`: The duration allowed for lane change + * - `lc_param_ptr->maximum_prepare_duration`: The maximum duration allowed for lane change * preparation. * - `bpp_param_ptr->max_vel`: The maximum velocity of the ego vehicle. * @@ -131,6 +131,24 @@ std::vector calc_lon_acceleration_samples( const CommonDataPtr & common_data_ptr, const double max_path_velocity, const double prepare_duration); +/** + * @brief calculates the actual prepare duration that will be used for path generation + * + * @details computes the required prepare duration to be used for candidate path + * generation based on the elapsed time of turn signal activation, the minimum + * and maximum parameterized values for the prepare duration, + * and the minimum lane changing velocity. + * + * @param common_data_ptr Shared pointer to a CommonData structure, which includes + * lane change parameters and bpp common parameters. + * @param current_velocity current ego vehicle velocity. + * @param active_signal_duration elapsed time since turn signal activation. + * @return The calculated prepare duration value in seconds (s) + */ +double calc_actual_prepare_duration( + const CommonDataPtr & common_data_ptr, const double current_velocity, + const double active_signal_duration); + std::vector calc_prepare_phase_metrics( const CommonDataPtr & common_data_ptr, const double current_velocity, const double max_path_velocity, const double min_length_threshold = 0.0, 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 32cf000ecb1a7..c121ab8512cce 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 @@ -222,6 +222,8 @@ struct TransientData size_t current_path_seg_idx; // index of nearest segment to ego along current path double current_path_velocity; // velocity of the current path at the ego position along the path + double lane_change_prepare_duration{0.0}; + bool is_ego_near_current_terminal_start{false}; bool is_ego_stuck{false}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp index 31bd5d94f09c8..a76742307e061 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp @@ -115,7 +115,8 @@ struct SafetyParameters struct TrajectoryParameters { - double prepare_duration{4.0}; + double max_prepare_duration{4.0}; + double min_prepare_duration{1.0}; double lateral_jerk{0.5}; double min_longitudinal_acc{-1.0}; double max_longitudinal_acc{1.0}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index 77bf32512c0dc..f80aad721a07c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -80,7 +80,7 @@ void LaneChangeInterface::updateData() module_type_->setPreviousModuleOutput(getPreviousModuleOutput()); module_type_->update_lanes(getCurrentStatus() == ModuleStatus::RUNNING); module_type_->update_filtered_objects(); - module_type_->update_transient_data(); + module_type_->update_transient_data(getCurrentStatus() == ModuleStatus::RUNNING); module_type_->updateSpecialData(); if (isWaitingApproval() || module_type_->isAbortState()) { @@ -155,10 +155,10 @@ BehaviorModuleOutput LaneChangeInterface::plan() BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() { - *prev_approved_path_ = getPreviousModuleOutput().path; - BehaviorModuleOutput out = getPreviousModuleOutput(); + *prev_approved_path_ = out.path; + module_type_->insert_stop_point(module_type_->get_current_lanes(), out.path); out.turn_signal_info = module_type_->get_current_turn_signal_info(); @@ -168,7 +168,7 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() setObjectsOfInterestData(data.current_obj_pose, data.obj_shape, color); } - path_reference_ = std::make_shared(getPreviousModuleOutput().reference_path); + path_reference_ = std::make_shared(out.reference_path); stop_pose_ = module_type_->getStopPose(); if (!module_type_->isValidPath()) { 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 baba4311e2175..1bb41069140e7 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 @@ -45,8 +45,10 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s // trajectory generation { - p.trajectory.prepare_duration = - getOrDeclareParameter(*node, parameter("trajectory.prepare_duration")); + p.trajectory.max_prepare_duration = + getOrDeclareParameter(*node, parameter("trajectory.max_prepare_duration")); + p.trajectory.min_prepare_duration = + getOrDeclareParameter(*node, parameter("trajectory.min_prepare_duration")); p.trajectory.lateral_jerk = getOrDeclareParameter(*node, parameter("trajectory.lateral_jerk")); p.trajectory.min_longitudinal_acc = @@ -67,8 +69,8 @@ LCParamPtr LaneChangeModuleManager::set_params(rclcpp::Node * node, const std::s getOrDeclareParameter(*node, parameter("trajectory.lat_acc_sampling_num")); const auto max_acc = getOrDeclareParameter(*node, "normal.max_acc"); - p.trajectory.min_lane_changing_velocity = - std::min(p.trajectory.min_lane_changing_velocity, max_acc * p.trajectory.prepare_duration); + p.trajectory.min_lane_changing_velocity = std::min( + p.trajectory.min_lane_changing_velocity, max_acc * p.trajectory.max_prepare_duration); // validation of trajectory parameters if (p.trajectory.lon_acc_sampling_num < 1 || p.trajectory.lat_acc_sampling_num < 1) { @@ -311,7 +313,10 @@ void LaneChangeModuleManager::updateModuleParams(const std::vector(parameters, ns + "prepare_duration", p->trajectory.prepare_duration); + updateParam( + parameters, ns + "max_prepare_duration", p->trajectory.max_prepare_duration); + updateParam( + parameters, ns + "min_prepare_duration", p->trajectory.min_prepare_duration); updateParam(parameters, ns + "lateral_jerk", p->trajectory.lateral_jerk); updateParam( parameters, ns + ".min_lane_changing_velocity", p->trajectory.min_lane_changing_velocity); 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 8769547550852..99e7cc73e59ff 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 @@ -131,7 +131,7 @@ void NormalLaneChange::update_lanes(const bool is_approved) *common_data_ptr_->lanes_polygon_ptr = create_lanes_polygon(common_data_ptr_); } -void NormalLaneChange::update_transient_data() +void NormalLaneChange::update_transient_data(const bool is_approved) { if ( !common_data_ptr_ || !common_data_ptr_->is_data_available() || @@ -150,6 +150,13 @@ void NormalLaneChange::update_transient_data() prev_module_output_.path.points.at(nearest_seg_idx).point.longitudinal_velocity_mps; transient_data.current_path_seg_idx = nearest_seg_idx; + const auto active_signal_duration = + signal_activation_time_ ? (clock_.now() - signal_activation_time_.value()).seconds() : 0.0; + transient_data.lane_change_prepare_duration = + is_approved ? status_.lane_change_path.info.duration.prepare + : calculation::calc_actual_prepare_duration( + common_data_ptr_, common_data_ptr_->get_ego_speed(), active_signal_duration); + std::tie(transient_data.lane_changing_length, transient_data.current_dist_buffer) = calculation::calc_lc_length_and_dist_buffer(common_data_ptr_, get_current_lanes()); @@ -328,6 +335,8 @@ TurnSignalInfo NormalLaneChange::get_current_turn_signal_info() const return get_terminal_turn_signal_info(); } + set_signal_activation_time(); + return get_turn_signal(getEgoPose(), getLaneChangePath().info.lane_changing_end); } @@ -356,9 +365,14 @@ TurnSignalInfo NormalLaneChange::get_terminal_turn_signal_info() const const auto nearest_yaw_threshold = common_param.ego_nearest_yaw_threshold; const auto current_nearest_seg_idx = common_data_ptr_->transient_data.current_path_seg_idx; - return getTurnSignalDecider().overwrite_turn_signal( + const auto turn_signal_info = getTurnSignalDecider().overwrite_turn_signal( path, current_pose, current_nearest_seg_idx, original_turn_signal_info, terminal_turn_signal_info, nearest_dist_threshold, nearest_yaw_threshold); + + set_signal_activation_time( + turn_signal_info.turn_signal.command != terminal_turn_signal_info.turn_signal.command); + + return turn_signal_info; } LaneChangePath NormalLaneChange::getLaneChangePath() const @@ -429,8 +443,6 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() output.path = utils::combinePath(output.path, *found_extended_path); } output.reference_path = getReferencePath(); - output.turn_signal_info = - get_turn_signal(getEgoPose(), status_.lane_change_path.info.lane_changing_end); if (isStopState()) { const auto current_velocity = getEgoVelocity(); @@ -446,12 +458,17 @@ BehaviorModuleOutput NormalLaneChange::generateOutput() extendOutputDrivableArea(output); + const auto turn_signal_info = + get_turn_signal(getEgoPose(), status_.lane_change_path.info.lane_changing_end); const auto current_seg_idx = planner_data_->findEgoSegmentIndex(output.path.points); output.turn_signal_info = planner_data_->turn_signal_decider.overwrite_turn_signal( output.path, getEgoPose(), current_seg_idx, prev_module_output_.turn_signal_info, - output.turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, + turn_signal_info, planner_data_->parameters.ego_nearest_dist_threshold, planner_data_->parameters.ego_nearest_yaw_threshold); + set_signal_activation_time( + output.turn_signal_info.turn_signal.command != turn_signal_info.turn_signal.command); + return output; } 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 index 68b2debecc4d2..3ba11d62a2be7 100644 --- 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 @@ -104,7 +104,7 @@ double calc_dist_to_last_fit_width( double calc_maximum_prepare_length(const CommonDataPtr & common_data_ptr) { - const auto max_prepare_duration = common_data_ptr->lc_param_ptr->trajectory.prepare_duration; + const auto max_prepare_duration = common_data_ptr->lc_param_ptr->trajectory.max_prepare_duration; const auto ego_max_speed = common_data_ptr->bpp_param_ptr->max_vel; return max_prepare_duration * ego_max_speed; @@ -197,7 +197,7 @@ std::vector calc_max_lane_change_lengths( const auto & params = common_data_ptr->lc_param_ptr->trajectory; const auto lat_jerk = params.lateral_jerk; - const auto t_prepare = params.prepare_duration; + const auto t_prepare = params.max_prepare_duration; const auto current_velocity = common_data_ptr->get_ego_speed(); const auto path_velocity = common_data_ptr->transient_data.current_path_velocity; @@ -400,18 +400,41 @@ double calc_lane_changing_acceleration( prepare_longitudinal_acc); } +double calc_actual_prepare_duration( + const CommonDataPtr & common_data_ptr, const double current_velocity, + const double active_signal_duration) +{ + const auto & params = common_data_ptr->lc_param_ptr->trajectory; + const auto min_lc_velocity = params.min_lane_changing_velocity; + + // need to ensure min prep duration is sufficient to reach minimum lane changing velocity + const auto min_prepare_duration = std::invoke([&]() -> double { + if (current_velocity >= min_lc_velocity) { + return params.min_prepare_duration; + } + const auto max_acc = + std::min(common_data_ptr->bpp_param_ptr->max_acc, params.max_longitudinal_acc); + if (max_acc < eps) { + return params.max_prepare_duration; + } + return (min_lc_velocity - current_velocity) / max_acc; + }); + + return std::max(params.max_prepare_duration - active_signal_duration, min_prepare_duration); +} + std::vector calc_prepare_durations(const CommonDataPtr & common_data_ptr) { const auto & lc_param_ptr = common_data_ptr->lc_param_ptr; const auto threshold = common_data_ptr->bpp_param_ptr->base_link2front + lc_param_ptr->min_length_for_turn_signal_activation; - const auto max_prepare_duration = lc_param_ptr->trajectory.prepare_duration; // TODO(Azu) this check seems to cause scenario failures. if (common_data_ptr->transient_data.dist_to_terminal_start >= threshold) { - return {max_prepare_duration}; + return {common_data_ptr->transient_data.lane_change_prepare_duration}; } + const auto max_prepare_duration = lc_param_ptr->trajectory.max_prepare_duration; std::vector prepare_durations; constexpr double step = 0.5; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp index 510fef2c07d7c..ea36e4dc6960a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp @@ -223,7 +223,7 @@ TEST_F(TestNormalLaneChange, testGetPathWhenInvalid) constexpr auto is_approved = true; normal_lane_change_->update_lanes(!is_approved); normal_lane_change_->update_filtered_objects(); - normal_lane_change_->update_transient_data(); + normal_lane_change_->update_transient_data(!is_approved); normal_lane_change_->updateLaneChangeStatus(); const auto & lc_status = normal_lane_change_->getLaneChangeStatus(); @@ -261,7 +261,7 @@ TEST_F(TestNormalLaneChange, testGetPathWhenValid) set_previous_approved_path(); normal_lane_change_->update_lanes(!is_approved); normal_lane_change_->update_filtered_objects(); - normal_lane_change_->update_transient_data(); + normal_lane_change_->update_transient_data(!is_approved); const auto lane_change_required = normal_lane_change_->isLaneChangeRequired(); ASSERT_TRUE(lane_change_required); From c1d3478cd719b95d0fc9dcd2f064924253dedb40 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Thu, 5 Dec 2024 09:27:21 +0900 Subject: [PATCH 235/273] chore(compare_map_segmentation): rename defined type (#9181) Signed-off-by: badai-nguyen --- .../node.hpp | 8 +++---- .../node.hpp | 12 +++++------ .../voxel_grid_map_loader.cpp | 5 +++-- .../voxel_grid_map_loader.hpp | 21 ++++++++++--------- 4 files changed, 24 insertions(+), 22 deletions(-) diff --git a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp index d6b65daa82267..33c9d9ff3c788 100644 --- a/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp +++ b/perception/autoware_compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp @@ -28,14 +28,14 @@ namespace autoware::compare_map_segmentation { -using PointCloud = typename pcl::Filter::PointCloud; -using PointCloudPtr = typename PointCloud::Ptr; -using PointCloudConstPtr = typename PointCloud::ConstPtr; +using FilteredPointCloud = typename pcl::Filter::PointCloud; +using FilteredPointCloudPtr = typename FilteredPointCloud::Ptr; +using FilteredPointCloudConstPtr = typename FilteredPointCloud::ConstPtr; class DistanceBasedStaticMapLoader : public VoxelGridStaticMapLoader { private: - PointCloudConstPtr map_ptr_; + FilteredPointCloudConstPtr map_ptr_; pcl::search::Search::Ptr tree_; public: diff --git a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp index 218f19601cd41..9fb81aa675655 100644 --- a/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp +++ b/perception/autoware_compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp @@ -29,14 +29,14 @@ namespace autoware::compare_map_segmentation { -using PointCloud = typename pcl::Filter::PointCloud; -using PointCloudPtr = typename PointCloud::Ptr; -using PointCloudConstPtr = typename PointCloud::ConstPtr; +using FilteredPointCloud = typename pcl::Filter::PointCloud; +using FilteredPointCloudPtr = typename FilteredPointCloud::Ptr; +using FilteredPointCloudConstPtr = typename FilteredPointCloud::ConstPtr; class VoxelDistanceBasedStaticMapLoader : public VoxelGridStaticMapLoader { private: - PointCloudConstPtr map_ptr_; + FilteredPointCloudConstPtr map_ptr_; pcl::search::Search::Ptr tree_; public: @@ -55,7 +55,7 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader { protected: private: - PointCloudConstPtr map_ptr_; + FilteredPointCloudConstPtr map_ptr_; /* data */ public: explicit VoxelDistanceBasedDynamicMapLoader( @@ -78,7 +78,7 @@ class VoxelDistanceBasedDynamicMapLoader : public VoxelGridDynamicMapLoader pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp); VoxelGridPointXYZ map_cell_voxel_grid_tmp; - PointCloudPtr map_cell_downsampled_pc_ptr_tmp; + FilteredPointCloudPtr map_cell_downsampled_pc_ptr_tmp; auto map_cell_voxel_input_tmp_ptr = std::make_shared>(map_cell_pc_tmp); 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 d55712f5b756e..e93b2097e583e 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 @@ -63,7 +63,7 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels( } bool VoxelGridMapLoader::is_close_to_neighbor_voxels( - const pcl::PointXYZ & point, const double distance_threshold, const PointCloudPtr & map, + const pcl::PointXYZ & point, const double distance_threshold, const FilteredPointCloudPtr & map, VoxelGridPointXYZ & voxel) const { // check map downsampled pc @@ -228,7 +228,8 @@ bool VoxelGridMapLoader::is_close_to_neighbor_voxels( bool VoxelGridMapLoader::is_in_voxel( const pcl::PointXYZ & src_point, const pcl::PointXYZ & target_point, - const double distance_threshold, const PointCloudPtr & map, VoxelGridPointXYZ & voxel) const + const double distance_threshold, const FilteredPointCloudPtr & map, + VoxelGridPointXYZ & voxel) const { int voxel_index = voxel.getCentroidIndexAt(voxel.getGridCoordinates(src_point.x, src_point.y, src_point.z)); 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 7faabf2266291..3685008ffc4fe 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 @@ -54,9 +54,9 @@ class VoxelGridEx : public pcl::VoxelGrid using pcl::VoxelGrid::div_b_; using pcl::VoxelGrid::inverse_leaf_size_; - using PointCloud = typename pcl::Filter::PointCloud; - using PointCloudPtr = typename PointCloud::Ptr; - using PointCloudConstPtr = typename PointCloud::ConstPtr; + using FilteredPointCloud = typename pcl::Filter::PointCloud; + using FilteredPointCloudPtr = typename FilteredPointCloud::Ptr; + using FilteredPointCloudConstPtr = typename FilteredPointCloud::ConstPtr; public: using pcl::VoxelGrid::leaf_layout_; @@ -93,8 +93,8 @@ class VoxelGridMapLoader public: using VoxelGridPointXYZ = VoxelGridEx; - using PointCloud = typename pcl::Filter::PointCloud; - using PointCloudPtr = typename PointCloud::Ptr; + using FilteredPointCloud = typename pcl::Filter::PointCloud; + using FilteredPointCloudPtr = typename FilteredPointCloud::Ptr; explicit VoxelGridMapLoader( rclcpp::Node * node, double leaf_size, double downsize_ratio_z_axis, std::string * tf_map_input_frame); @@ -106,11 +106,12 @@ class VoxelGridMapLoader const pcl::PointXYZ & point, const double distance_threshold, VoxelGridPointXYZ & voxel, pcl::search::Search::Ptr tree); bool is_close_to_neighbor_voxels( - const pcl::PointXYZ & point, const double distance_threshold, const PointCloudPtr & map, + const pcl::PointXYZ & point, const double distance_threshold, const FilteredPointCloudPtr & map, VoxelGridPointXYZ & voxel) const; bool is_in_voxel( const pcl::PointXYZ & src_point, const pcl::PointXYZ & target_point, - const double distance_threshold, const PointCloudPtr & map, VoxelGridPointXYZ & voxel) const; + const double distance_threshold, const FilteredPointCloudPtr & map, + VoxelGridPointXYZ & voxel) const; void publish_downsampled_map(const pcl::PointCloud & downsampled_pc); std::string * tf_map_input_frame_; @@ -121,7 +122,7 @@ class VoxelGridStaticMapLoader : public VoxelGridMapLoader protected: rclcpp::Subscription::SharedPtr sub_map_; VoxelGridPointXYZ voxel_grid_; - PointCloudPtr voxel_map_ptr_; + FilteredPointCloudPtr voxel_map_ptr_; std::atomic_bool is_initialized_{false}; public: @@ -138,7 +139,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader struct MapGridVoxelInfo { VoxelGridPointXYZ map_cell_voxel_grid; - PointCloudPtr map_cell_pc_ptr; + FilteredPointCloudPtr map_cell_pc_ptr; float min_b_x, min_b_y, max_b_x, max_b_y; pcl::search::Search::Ptr map_cell_kdtree; }; @@ -291,7 +292,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader pcl::fromROSMsg(map_cell_to_add.pointcloud, map_cell_pc_tmp); VoxelGridPointXYZ map_cell_voxel_grid_tmp; - PointCloudPtr map_cell_downsampled_pc_ptr_tmp; + FilteredPointCloudPtr map_cell_downsampled_pc_ptr_tmp; auto map_cell_voxel_input_tmp_ptr = std::make_shared>(map_cell_pc_tmp); From ae9392fc67f7a6f54863cb24a488c657af89b8df Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 5 Dec 2024 10:26:58 +0900 Subject: [PATCH 236/273] refactor(lane_departure_checker): move member functions to util functions (#9547) * refactor(lane_departure_checker): move member functions to util functions Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../lane_departure_checker.hpp | 3 - .../autoware/lane_departure_checker/utils.hpp | 32 ++++++++++ .../lane_departure_checker.cpp | 58 ++---------------- .../src/lane_departure_checker_node/utils.cpp | 59 +++++++++++++++++++ 4 files changed, 97 insertions(+), 55 deletions(-) diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp index da4784bb2458a..1ac984394a25e 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/lane_departure_checker.hpp @@ -157,9 +157,6 @@ class LaneDepartureChecker Param param_; std::shared_ptr vehicle_info_ptr_; - static std::vector createVehiclePassingAreas( - const std::vector & vehicle_footprints); - bool willLeaveLane( const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints) const; diff --git a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/utils.hpp b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/utils.hpp index 944c57f66b8f1..bde404603749b 100644 --- a/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/utils.hpp +++ b/control/autoware_lane_departure_checker/include/autoware/lane_departure_checker/utils.hpp @@ -24,11 +24,16 @@ #include #include +#include +#include +#include + #include namespace autoware::lane_departure_checker::utils { using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::MultiPoint2d; using autoware::universe_utils::PoseDeviation; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; @@ -76,6 +81,33 @@ std::vector createVehicleFootprints( const PathWithLaneId & path, const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double footprint_extra_margin); +/** + * @brief find lanelets that potentially intersect with the vehicle's trajectory + * @param route_lanelets lanelets along the planned route + * @param vehicle_footprints series of vehicle footprint polygons along the trajectory + * @return lanelets that are not disjoint from the convex hull of vehicle footprints + */ +lanelet::ConstLanelets getCandidateLanelets( + const lanelet::ConstLanelets & route_lanelets, + const std::vector & vehicle_footprints); + +/** + * @brief create a convex hull from multiple footprint polygons + * @param footprints collection of footprint polygons represented as LinearRing2d + * @return a single LinearRing2d representing the convex hull containing all input footprints + */ +LinearRing2d createHullFromFootprints(const std::vector & footprints); + +/** + * @brief create passing areas of the vehicle from vehicle footprints + * @param vehicle_footprints vehicle footprints along trajectory + * @return passing areas of the vehicle that are created from adjacent vehicle footprints + * If vehicle_footprints is empty, returns empty vector + * If vehicle_footprints size is 1, returns vector with that footprint + */ +std::vector createVehiclePassingAreas( + const std::vector & vehicle_footprints); + /** * @brief calculate the deviation of the given pose from the nearest pose on the trajectory * @param trajectory target trajectory diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp index 1c75b3552df67..5d50ac0e2951b 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp @@ -59,39 +59,6 @@ bool isInAnyLane(const lanelet::ConstLanelets & candidate_lanelets, const Point2 return false; } -LinearRing2d createHullFromFootprints(const std::vector & footprints) -{ - MultiPoint2d combined; - for (const auto & footprint : footprints) { - for (const auto & p : footprint) { - combined.push_back(p); - } - } - - LinearRing2d hull; - boost::geometry::convex_hull(combined, hull); - - return hull; -} - -lanelet::ConstLanelets getCandidateLanelets( - const lanelet::ConstLanelets & route_lanelets, - const std::vector & vehicle_footprints) -{ - lanelet::ConstLanelets candidate_lanelets; - - // Find lanes within the convex hull of footprints - const auto footprint_hull = createHullFromFootprints(vehicle_footprints); - for (const auto & route_lanelet : route_lanelets) { - const auto poly = route_lanelet.polygon2d().basicPolygon(); - if (!boost::geometry::disjoint(poly, footprint_hull)) { - candidate_lanelets.push_back(route_lanelet); - } - } - - return candidate_lanelets; -} - } // namespace namespace autoware::lane_departure_checker @@ -126,13 +93,13 @@ Output LaneDepartureChecker::update(const Input & input) param_.footprint_margin_scale); output.processing_time_map["createVehicleFootprints"] = stop_watch.toc(true); - output.vehicle_passing_areas = createVehiclePassingAreas(output.vehicle_footprints); + output.vehicle_passing_areas = utils::createVehiclePassingAreas(output.vehicle_footprints); output.processing_time_map["createVehiclePassingAreas"] = stop_watch.toc(true); const auto candidate_road_lanelets = - getCandidateLanelets(input.route_lanelets, output.vehicle_footprints); + utils::getCandidateLanelets(input.route_lanelets, output.vehicle_footprints); const auto candidate_shoulder_lanelets = - getCandidateLanelets(input.shoulder_lanelets, output.vehicle_footprints); + utils::getCandidateLanelets(input.shoulder_lanelets, output.vehicle_footprints); output.candidate_lanelets = candidate_road_lanelets; output.candidate_lanelets.insert( output.candidate_lanelets.end(), candidate_shoulder_lanelets.begin(), @@ -164,24 +131,11 @@ bool LaneDepartureChecker::checkPathWillLeaveLane( std::vector vehicle_footprints = utils::createVehicleFootprints(path, *vehicle_info_ptr_, param_.footprint_extra_margin); - lanelet::ConstLanelets candidate_lanelets = getCandidateLanelets(lanelets, vehicle_footprints); + lanelet::ConstLanelets candidate_lanelets = + utils::getCandidateLanelets(lanelets, vehicle_footprints); return willLeaveLane(candidate_lanelets, vehicle_footprints); } -std::vector LaneDepartureChecker::createVehiclePassingAreas( - const std::vector & vehicle_footprints) -{ - // Create hull from two adjacent vehicle footprints - std::vector areas; - for (size_t i = 0; i < vehicle_footprints.size() - 1; ++i) { - const auto & footprint1 = vehicle_footprints.at(i); - const auto & footprint2 = vehicle_footprints.at(i + 1); - areas.push_back(createHullFromFootprints({footprint1, footprint2})); - } - - return areas; -} - bool LaneDepartureChecker::willLeaveLane( const lanelet::ConstLanelets & candidate_lanelets, const std::vector & vehicle_footprints) const @@ -205,7 +159,7 @@ std::vector> LaneDepartureChecker::getLanele // Get Footprint Hull basic polygon std::vector vehicle_footprints = utils::createVehicleFootprints(path, *vehicle_info_ptr_, param_.footprint_extra_margin); - LinearRing2d footprint_hull = createHullFromFootprints(vehicle_footprints); + LinearRing2d footprint_hull = utils::createHullFromFootprints(vehicle_footprints); lanelet::BasicPolygon2d footprint_hull_basic_polygon = toBasicPolygon2D(footprint_hull); diff --git a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp index 5613b767a9fd0..ec0647115385d 100644 --- a/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp +++ b/control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp @@ -19,6 +19,8 @@ #include +#include + #include namespace @@ -165,6 +167,63 @@ std::vector createVehicleFootprints( return vehicle_footprints; } +lanelet::ConstLanelets getCandidateLanelets( + const lanelet::ConstLanelets & route_lanelets, + const std::vector & vehicle_footprints) +{ + lanelet::ConstLanelets candidate_lanelets; + + // Find lanes within the convex hull of footprints + const auto footprint_hull = createHullFromFootprints(vehicle_footprints); + + for (const auto & route_lanelet : route_lanelets) { + const auto poly = route_lanelet.polygon2d().basicPolygon(); + if (!boost::geometry::disjoint(poly, footprint_hull)) { + candidate_lanelets.push_back(route_lanelet); + } + } + + return candidate_lanelets; +} + +LinearRing2d createHullFromFootprints(const std::vector & footprints) +{ + MultiPoint2d combined; + for (const auto & footprint : footprints) { + for (const auto & p : footprint) { + combined.push_back(p); + } + } + + LinearRing2d hull; + boost::geometry::convex_hull(combined, hull); + + return hull; +} + +std::vector createVehiclePassingAreas( + const std::vector & vehicle_footprints) +{ + if (vehicle_footprints.empty()) { + return {}; + } + + if (vehicle_footprints.size() == 1) { + return {vehicle_footprints.front()}; + } + + std::vector areas; + areas.reserve(vehicle_footprints.size() - 1); + + for (size_t i = 0; i < vehicle_footprints.size() - 1; ++i) { + const auto & footprint1 = vehicle_footprints.at(i); + const auto & footprint2 = vehicle_footprints.at(i + 1); + areas.push_back(createHullFromFootprints({footprint1, footprint2})); + } + + return areas; +} + PoseDeviation calcTrajectoryDeviation( const Trajectory & trajectory, const geometry_msgs::msg::Pose & pose, const double dist_threshold, const double yaw_threshold) From a1f69de9e405daddbe89da95ed7e8b78eeb43f87 Mon Sep 17 00:00:00 2001 From: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> Date: Thu, 5 Dec 2024 11:16:42 +0900 Subject: [PATCH 237/273] test(lane_departure_checker): add unit test for createVehiclePassingAreas (#9548) * test(lane_departure_checker): add unit tests for createVehiclePassingAreas function Signed-off-by: kyoichi-sugahara --------- Signed-off-by: kyoichi-sugahara --- .../test_create_vehicle_passing_areas.cpp | 164 ++++++++++++++++++ 1 file changed, 164 insertions(+) create mode 100644 control/autoware_lane_departure_checker/test/test_create_vehicle_passing_areas.cpp diff --git a/control/autoware_lane_departure_checker/test/test_create_vehicle_passing_areas.cpp b/control/autoware_lane_departure_checker/test/test_create_vehicle_passing_areas.cpp new file mode 100644 index 0000000000000..d79ebeb1e13e3 --- /dev/null +++ b/control/autoware_lane_departure_checker/test/test_create_vehicle_passing_areas.cpp @@ -0,0 +1,164 @@ +// 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/lane_departure_checker/utils.hpp" + +#include +#include + +#include +#include +#include +#include + +#include + +using autoware::lane_departure_checker::utils::createVehiclePassingAreas; +using autoware::universe_utils::LinearRing2d; +using autoware::universe_utils::Point2d; + +class CreateVehiclePassingAreasTest : public ::testing::Test +{ +protected: + LinearRing2d createSquare(double x, double y, double size) + { + LinearRing2d square; + square.reserve(5); + square.push_back(Point2d{x, y}); // bottom-left + square.push_back(Point2d{x, y + size}); // top-left + square.push_back(Point2d{x + size, y + size}); // top-right + square.push_back(Point2d{x + size, y}); // bottom-right + square.push_back(Point2d{x, y}); // close the square + boost::geometry::correct(square); + return square; + } + + bool isPointInsideHull(const Point2d & point, const LinearRing2d & hull) + { + return boost::geometry::within(point, hull) || boost::geometry::covered_by(point, hull); + } + + /** + * @brief Validates that all points in the given footprints are contained within the hull + * + * For each footprint in the input vector, checks whether all its points (except the last one + * which is identical to the first point in a LinearRing2d) are contained within the given hull. + * This validation ensures the correctness of the convex hull generation for vehicle passing + * areas. + * + * @param footprints Vector of LinearRing2d representing vehicle footprints to validate + * Must not be empty and must not contain empty LinearRing2d + * @param hull LinearRing2d representing the convex hull that should contain all footprints + * @note The last point of each footprint is not checked as LinearRing2d is a closed ring + * where the last point is identical to the first point + * @pre footprints must not be empty + * @pre each LinearRing2d in footprints must not be empty, as it represents a closed ring + */ + void validateFootprintsInHull( + const std::vector & footprints, const LinearRing2d & hull) + { + for (const auto & footprint : footprints) { + // An empty footprint would be invalid and should fail the test + EXPECT_FALSE(footprint.empty()) << "Footprint must not be empty"; + if (footprint.empty()) { + continue; + } + + // Iterate up to size()-1 since LinearRing2d is a closed ring where + // the last point is the same as the first point, so we don't need + // to check it again + for (size_t i = 0; i < footprint.size() - 1; ++i) { + const auto & point = footprint[i]; + EXPECT_TRUE(isPointInsideHull(point, hull)) + << "Point (" << point.x() << ", " << point.y() << ") is not inside the hull"; + } + } + } + + void SetUp() override + { + /* + Square placement: + Y-axis + ^ + | + 1 +---+ +---+ +---+ + | |s1 | |s2 | |s3 | + 0 +---+ +---+ +---+ + | + +---+---+---+---+---+---+--> X-axis + 0 1 1 2 3 4 + + s1: square1_ from (0,0) to (1,1) + s2: square2_ from (1,0) to (2,1) - adjacent to s1 + s3: square3_ from (3,0) to (4,1) - 1 unit apart from s2 + */ + square1_ = createSquare(0.0, 0.0, 1.0); // 1x1 square at origin + square2_ = createSquare(1.0, 0.0, 1.0); // square adjacent to square1_ + square3_ = createSquare(3.0, 0.0, 1.0); // square one unit apart from square2_ + } + + LinearRing2d square1_; // Reference square (0,0) + LinearRing2d square2_; // Adjacent square (1,0) + LinearRing2d square3_; // Distant square (3,0) +}; + +TEST_F(CreateVehiclePassingAreasTest, ReturnsEmptyAreaForEmptyInput) +{ + const std::vector empty_footprints; + const auto areas = createVehiclePassingAreas(empty_footprints); + EXPECT_TRUE(areas.empty()); +} + +TEST_F(CreateVehiclePassingAreasTest, ReturnsSameAreaForSingleFootprint) +{ + const std::vector single_footprint = {square1_}; + const auto areas = createVehiclePassingAreas(single_footprint); + + ASSERT_EQ(areas.size(), 1); + + auto result = areas.front(); + boost::geometry::correct(result); + EXPECT_EQ(result, square1_); +} + +TEST_F(CreateVehiclePassingAreasTest, CreatesValidHullForAdjacentFootprints) +{ + const std::vector footprints = {square1_, square2_}; + auto areas = createVehiclePassingAreas(footprints); + + ASSERT_EQ(areas.size(), 1); + auto & hull = areas.front(); + boost::geometry::correct(hull); + + // Basic validation of the convex hull + EXPECT_GE(hull.size(), 5); // At least a quadrilateral plus closing point + + // Verify all points from original footprints are inside the hull + validateFootprintsInHull(footprints, hull); +} + +TEST_F(CreateVehiclePassingAreasTest, HandlesNonAdjacentFootprints) +{ + const std::vector footprints = { + square1_, square3_}; // Using square3_ which is not adjacent to square1_ + auto areas = createVehiclePassingAreas(footprints); + + ASSERT_EQ(areas.size(), 1); + auto & hull = areas.front(); + boost::geometry::correct(hull); + + // Verify all points are inside the hull even for non-adjacent squares + validateFootprintsInHull(footprints, hull); +} From eae7b542717ffaa3347cb13970006c1fa007987f Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 5 Dec 2024 11:47:32 +0900 Subject: [PATCH 238/273] fix(autoware_multi_object_tracker): measure latency with latest detection update time (#9533) * fix: measure latency with latest detection update time Signed-off-by: Taekjin LEE * fix: remove duplicated current_time Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../src/multi_object_tracker_node.cpp | 28 ++++++--------- .../src/multi_object_tracker_node.hpp | 1 - .../src/processor/input_manager.cpp | 36 +++++++++---------- .../src/processor/input_manager.hpp | 4 +-- 4 files changed, 31 insertions(+), 38 deletions(-) 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 d55ff3ab1f0bb..a8e27ed4f0146 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 @@ -214,7 +214,17 @@ 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); + + // process start + last_updated_time_ = current_time; + const rclcpp::Time latest_time(objects_list.back().second.header.stamp); + debugger_->startMeasurementTime(this->now(), latest_time); + // run process for each DetectedObjects + for (const auto & objects_data : objects_list) { + runProcess(objects_data.second, objects_data.first); + } + // process end + debugger_->endMeasurementTime(this->now()); // Publish without delay compensation if (!publish_timer_) { @@ -246,22 +256,6 @@ void MultiObjectTracker::onTimer() if (should_publish) checkAndPublish(current_time); } -void MultiObjectTracker::onMessage(const ObjectsList & objects_list) -{ - const rclcpp::Time current_time = this->now(); - const rclcpp::Time oldest_time(objects_list.front().second.header.stamp); - last_updated_time_ = current_time; - - // process start - debugger_->startMeasurementTime(this->now(), oldest_time); - // run process for each DetectedObjects - for (const auto & objects_data : objects_list) { - runProcess(objects_data.second, objects_data.first); - } - // process end - debugger_->endMeasurementTime(this->now()); -} - void MultiObjectTracker::runProcess( const DetectedObjects & input_objects, const uint & channel_index) { 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 b9886ee3fc847..79a8c1b98dcca 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 @@ -98,7 +98,6 @@ class MultiObjectTracker : public rclcpp::Node // callback functions void onTimer(); void onTrigger(); - void onMessage(const ObjectsList & objects_list); // publish processes void runProcess(const DetectedObjects & input_objects, const uint & channel_index); diff --git a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp index 5b8fd23999a95..fa333ea06a4b9 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.cpp @@ -146,22 +146,22 @@ void InputStream::updateTimingStatus(const rclcpp::Time & now, const rclcpp::Tim } void InputStream::getObjectsOlderThan( - const rclcpp::Time & object_latest_time, const rclcpp::Time & object_oldest_time, + const rclcpp::Time & object_latest_time, const rclcpp::Time & object_earliest_time, ObjectsList & objects_list) { - if (object_latest_time < object_oldest_time) { + if (object_latest_time < object_earliest_time) { RCLCPP_WARN( node_.get_logger(), "InputManager::getObjectsOlderThan %s: Invalid object time interval, object_latest_time: %f, " - "object_oldest_time: %f", - long_name_.c_str(), object_latest_time.seconds(), object_oldest_time.seconds()); + "object_earliest_time: %f", + long_name_.c_str(), object_latest_time.seconds(), object_earliest_time.seconds()); return; } for (const auto & objects : objects_que_) { const rclcpp::Time object_time = rclcpp::Time(objects.header.stamp); // ignore objects older than the specified duration - if (object_time < object_oldest_time) { + if (object_time < object_earliest_time) { continue; } @@ -240,7 +240,7 @@ void InputManager::onTrigger(const uint & index) const void InputManager::getObjectTimeInterval( const rclcpp::Time & now, rclcpp::Time & object_latest_time, - rclcpp::Time & object_oldest_time) const + rclcpp::Time & object_earliest_time) const { // Set the object time interval @@ -259,19 +259,19 @@ void InputManager::getObjectTimeInterval( object_latest_time < latest_measurement_time ? latest_measurement_time : object_latest_time; } - // 2. object_oldest_time - // The default object_oldest_time is to have a 1-second time interval - const rclcpp::Time object_oldest_time_default = + // 2. object_earliest_time + // The default object_earliest_time is to have a 1-second time interval + const rclcpp::Time object_earliest_time_default = object_latest_time - rclcpp::Duration::from_seconds(1.0); - if (latest_exported_object_time_ < object_oldest_time_default) { + if (latest_exported_object_time_ < object_earliest_time_default) { // if the latest exported object time is too old, set to the default - object_oldest_time = object_oldest_time_default; + object_earliest_time = object_earliest_time_default; } else if (latest_exported_object_time_ > object_latest_time) { // if the latest exported object time is newer than the object_latest_time, set to the default - object_oldest_time = object_oldest_time_default; + object_earliest_time = object_earliest_time_default; } else { - // The object_oldest_time is the latest exported object time - object_oldest_time = latest_exported_object_time_; + // The object_earliest_time is the latest exported object time + object_earliest_time = latest_exported_object_time_; } } @@ -322,8 +322,8 @@ bool InputManager::getObjects(const rclcpp::Time & now, ObjectsList & objects_li // Get the time interval for the objects rclcpp::Time object_latest_time; - rclcpp::Time object_oldest_time; - getObjectTimeInterval(now, object_latest_time, object_oldest_time); + rclcpp::Time object_earliest_time; + getObjectTimeInterval(now, object_latest_time, object_earliest_time); // Optimize the target stream, latency, and its band // The result will be used for the next time, so the optimization is after getting the time @@ -333,7 +333,7 @@ bool InputManager::getObjects(const rclcpp::Time & now, ObjectsList & objects_li // Get objects from all input streams // adds up to the objects vector for efficient processing for (const auto & input_stream : input_streams_) { - input_stream->getObjectsOlderThan(object_latest_time, object_oldest_time, objects_list); + input_stream->getObjectsOlderThan(object_latest_time, object_earliest_time, objects_list); } // Sort objects by timestamp @@ -365,7 +365,7 @@ bool InputManager::getObjects(const rclcpp::Time & now, ObjectsList & objects_li RCLCPP_DEBUG( node_.get_logger(), "InputManager::getObjects No objects in the object list, object time band from %f to %f", - (now - object_oldest_time).seconds(), (now - object_latest_time).seconds()); + (now - object_earliest_time).seconds(), (now - object_latest_time).seconds()); } } 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 25ee6b5eb0d5a..01b3148251743 100644 --- a/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp +++ b/perception/autoware_multi_object_tracker/src/processor/input_manager.hpp @@ -57,7 +57,7 @@ class InputStream bool isTimeInitialized() const { return initial_count_ > 0; } uint getIndex() const { return index_; } void getObjectsOlderThan( - const rclcpp::Time & object_latest_time, const rclcpp::Time & object_oldest_time, + const rclcpp::Time & object_latest_time, const rclcpp::Time & object_earliest_time, ObjectsList & objects_list); bool isSpawnEnabled() const { return is_spawn_enabled_; } @@ -133,7 +133,7 @@ class InputManager private: void getObjectTimeInterval( const rclcpp::Time & now, rclcpp::Time & object_latest_time, - rclcpp::Time & object_oldest_time) const; + rclcpp::Time & object_earliest_time) const; void optimizeTimings(); }; From f957912fab7b33c8baa2e07276506c23f480a079 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 5 Dec 2024 11:52:11 +0900 Subject: [PATCH 239/273] chore(autoware_autonomous_emergency_braking): add package maintainer (#9580) add package maintainer Signed-off-by: mohammad alqudah --- control/autoware_autonomous_emergency_braking/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/control/autoware_autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml index edec3ac8fd6a1..5fac12cb3e715 100644 --- a/control/autoware_autonomous_emergency_braking/package.xml +++ b/control/autoware_autonomous_emergency_braking/package.xml @@ -9,6 +9,7 @@ Mamoru Sobue Daniel Sanchez Kyoichi Sugahara + Alqudah Mohammad Apache License 2.0 From 6b5b42a8d2f448ed722674e24c8b9eee84cd61ea Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Thu, 5 Dec 2024 12:28:37 +0900 Subject: [PATCH 240/273] chore(autoware_behavior_path_static_obstacle_avoidance_module): add maintainer (#9581) Signed-off-by: Y.Hisaki --- .../package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml index 0a990ddf4cb52..ca7a2dab1191c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml @@ -14,6 +14,7 @@ Shumpei Wakabayashi Tomohito Ando Go Sakayori + Yukinari Hisaki Apache License 2.0 From e75bbbc1825c69b25e59c153a0f4682bf99de52b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Thu, 5 Dec 2024 09:10:18 +0300 Subject: [PATCH 241/273] feat(bytetrack): remove unreachable code block from lapjv.h (#9563) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .../autoware_bytetrack/lib/include/lapjv.h | 30 ------------------- 1 file changed, 30 deletions(-) diff --git a/perception/autoware_bytetrack/lib/include/lapjv.h b/perception/autoware_bytetrack/lib/include/lapjv.h index d197b747e6f7d..c42fcbac8eb60 100644 --- a/perception/autoware_bytetrack/lib/include/lapjv.h +++ b/perception/autoware_bytetrack/lib/include/lapjv.h @@ -64,40 +64,10 @@ b = _temp_index; \ } -#if 0 -#include -#define ASSERT(cond) assert(cond) -#define PRINTF(fmt, ...) printf(fmt, ##__VA_ARGS__) -#define PRINT_COST_ARRAY(a, n) \ - while (1) { \ - printf(#a " = ["); \ - if ((n) > 0) { \ - printf("%f", (a)[0]); \ - for (uint_t j = 1; j < n; j++) { \ - printf(", %f", (a)[j]); \ - } \ - } \ - printf("]\n"); \ - break; \ - } -#define PRINT_INDEX_ARRAY(a, n) \ - while (1) { \ - printf(#a " = ["); \ - if ((n) > 0) { \ - printf("%d", (a)[0]); \ - for (uint_t j = 1; j < n; j++) { \ - printf(", %d", (a)[j]); \ - } \ - } \ - printf("]\n"); \ - break; \ - } -#else #define ASSERT(cond) #define PRINTF(fmt, ...) #define PRINT_COST_ARRAY(a, n) #define PRINT_INDEX_ARRAY(a, n) -#endif typedef signed int int_t; typedef unsigned int uint_t; From cf0266e5cde240608d5038ab3e190bc3bfc5d219 Mon Sep 17 00:00:00 2001 From: mkquda <168697710+mkquda@users.noreply.github.com> Date: Thu, 5 Dec 2024 15:44:13 +0900 Subject: [PATCH 242/273] feat(costmap_generator, scenario_selector): improve freespace planning stability (#9579) * discretize updating grid center position by size of grid resolution Signed-off-by: mohammad alqudah * modify logic for switching to lane driving in scenario selector Signed-off-by: mohammad alqudah * fix spelling Signed-off-by: mohammad alqudah --------- Signed-off-by: mohammad alqudah --- .../costmap_generator/costmap_generator.hpp | 11 ++++++++- .../src/costmap_generator.cpp | 24 +++++++++++++------ .../autoware_scenario_selector/src/node.cpp | 22 ++++++++++++++--- 3 files changed, 46 insertions(+), 11 deletions(-) diff --git a/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp b/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp index 72b56f0348a40..4fed5bcb6cff3 100644 --- a/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp +++ b/planning/autoware_costmap_generator/include/autoware/costmap_generator/costmap_generator.hpp @@ -139,6 +139,13 @@ class CostmapGenerator : public rclcpp::Node void set_current_pose(); + /// \brief set position of grid center + /// \details computes relative position of ego from current grid center, + /// if offset is larger than grid resolution, grid center will be updated + /// by a multiple of the grid resolution + /// \param[in] tf costmap frame to vehicle frame transform + void set_grid_center(const geometry_msgs::msg::TransformStamped & tf); + void onTimer(); bool isActive(); @@ -148,7 +155,9 @@ class CostmapGenerator : public rclcpp::Node /// \brief publish ros msg: grid_map::GridMap, and nav_msgs::OccupancyGrid /// \param[in] gridmap with calculated cost - void publishCostmap(const grid_map::GridMap & costmap); + /// \param[in] tf costmap frame to vehicle frame transform + void publishCostmap( + const grid_map::GridMap & costmap, const geometry_msgs::msg::TransformStamped & tf); /// \brief fill a vector with road area polygons /// \param [in] lanelet_map input lanelet map diff --git a/planning/autoware_costmap_generator/src/costmap_generator.cpp b/planning/autoware_costmap_generator/src/costmap_generator.cpp index 4092acae9b51c..052bb2728a3b1 100644 --- a/planning/autoware_costmap_generator/src/costmap_generator.cpp +++ b/planning/autoware_costmap_generator/src/costmap_generator.cpp @@ -286,11 +286,7 @@ void CostmapGenerator::onTimer() } time_keeper_->end_track("lookupTransform"); - // Set grid center - grid_map::Position p; - p.x() = tf.transform.translation.x; - p.y() = tf.transform.translation.y; - costmap_.setPosition(p); + set_grid_center(tf); if ((param_->use_wayarea || param_->use_parkinglot) && lanelet_map_) { autoware::universe_utils::ScopedTimeTrack st("generatePrimitivesCostmap()", *time_keeper_); @@ -312,7 +308,18 @@ void CostmapGenerator::onTimer() costmap_[LayerName::combined] = generateCombinedCostmap(); } - publishCostmap(costmap_); + publishCostmap(costmap_, tf); +} + +void CostmapGenerator::set_grid_center(const geometry_msgs::msg::TransformStamped & tf) +{ + const auto cur_pos = costmap_.getPosition(); + const grid_map::Position ref_pos(tf.transform.translation.x, tf.transform.translation.y); + const auto disp = ref_pos - cur_pos; + const auto resolution = costmap_.getResolution(); + const grid_map::Position offset( + std::round(disp.x() / resolution) * resolution, std::round(disp.y() / resolution) * resolution); + costmap_.setPosition(cur_pos + offset); } bool CostmapGenerator::isActive() @@ -452,7 +459,8 @@ grid_map::Matrix CostmapGenerator::generateCombinedCostmap() return combined_costmap[LayerName::combined]; } -void CostmapGenerator::publishCostmap(const grid_map::GridMap & costmap) +void CostmapGenerator::publishCostmap( + const grid_map::GridMap & costmap, const geometry_msgs::msg::TransformStamped & tf) { // Set header std_msgs::msg::Header header; @@ -465,11 +473,13 @@ void CostmapGenerator::publishCostmap(const grid_map::GridMap & costmap) costmap, LayerName::combined, param_->grid_min_value, param_->grid_max_value, out_occupancy_grid); out_occupancy_grid.header = header; + out_occupancy_grid.info.origin.position.z = tf.transform.translation.z; pub_occupancy_grid_->publish(out_occupancy_grid); // Publish GridMap auto out_gridmap_msg = grid_map::GridMapRosConverter::toMessage(costmap); out_gridmap_msg->header = header; + out_gridmap_msg->info.pose.position.z = tf.transform.translation.z; pub_costmap_->publish(*out_gridmap_msg); // Publish ProcessingTime diff --git a/planning/autoware_scenario_selector/src/node.cpp b/planning/autoware_scenario_selector/src/node.cpp index eb3303766205f..4bb64e27368d8 100644 --- a/planning/autoware_scenario_selector/src/node.cpp +++ b/planning/autoware_scenario_selector/src/node.cpp @@ -14,6 +14,7 @@ #include "autoware/scenario_selector/node.hpp" +#include #include #include @@ -65,6 +66,22 @@ bool isInLane( return dist_to_nearest_lanelet < margin; } +bool isAlongLane( + const std::shared_ptr & route_handler, + const geometry_msgs::msg::Pose & current_pose) +{ + lanelet::ConstLanelet closest_lanelet; + if (!route_handler->getClosestLaneletWithConstrainsWithinRoute( + current_pose, &closest_lanelet, 0.0, M_PI_4)) { + return false; + } + const lanelet::BasicPoint2d src_point(current_pose.position.x, current_pose.position.y); + const auto dist_to_centerline = + lanelet::geometry::distanceToCenterline2d(closest_lanelet, src_point); + static constexpr double margin = 1.0; + return dist_to_centerline < margin; +} + bool isInParkingLot( const std::shared_ptr & lanelet_map_ptr, const geometry_msgs::msg::Pose & current_pose) @@ -215,10 +232,9 @@ bool ScenarioSelectorNode::isSwitchToParking(const bool is_stopped) bool ScenarioSelectorNode::isSwitchToLaneDriving() { - const auto is_in_lane = - isInLane(route_handler_->getLaneletMapPtr(), current_pose_->pose.pose.position); + const auto is_along_lane = isAlongLane(route_handler_, current_pose_->pose.pose); - if (!isEmptyParkingTrajectory() || !is_in_lane) { + if (!isEmptyParkingTrajectory() || !is_along_lane) { empty_parking_trajectory_time_ = {}; return false; } From 1aba360508814fdf781e2a5c197b99b1c989dca3 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 5 Dec 2024 19:01:44 +0900 Subject: [PATCH 243/273] refactor(goal_planner): improve log message and change level (#9562) Signed-off-by: kosuke55 Co-authored-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> --- .../src/goal_planner_module.cpp | 34 ++++++++++++------- 1 file changed, 22 insertions(+), 12 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 120a2fa6c24ec..01d06a4964c61 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -103,7 +103,10 @@ GoalPlannerModule::GoalPlannerModule( } if (pull_over_planners_.empty()) { - RCLCPP_ERROR(getLogger(), "Not found enabled planner"); + RCLCPP_WARN( + getLogger(), + "No enabled planner found. The vehicle will stop in the road lane without pull over. Please " + "check the parameters if this is the intended behavior."); } // set selected goal searcher @@ -296,8 +299,8 @@ void GoalPlannerModule::onTimer() !local_planner_data || !current_status_opt || !previous_module_output_opt || !last_previous_module_output_opt || !occupancy_grid_map || !parameters_opt || !goal_candidates_opt) { - RCLCPP_ERROR( - getLogger(), + RCLCPP_INFO_THROTTLE( + getLogger(), *clock_, 5000, "failed to get valid " "local_planner_data/current_status/previous_module_output/occupancy_grid_map/parameters_opt " "in onTimer"); @@ -462,8 +465,8 @@ void GoalPlannerModule::onFreespaceParkingTimer() if ( !local_planner_data || !current_status_opt || !occupancy_grid_map || !parameters_opt || !vehicle_footprint_opt || !goal_candidates_opt) { - RCLCPP_ERROR( - getLogger(), + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 5000, "failed to get valid planner_data/current_status/parameters in " "onFreespaceParkingTimer"); return; @@ -801,7 +804,9 @@ bool GoalPlannerModule::isExecutionReady() const // path_decision_controller.get_current_state() is valid if (parameters_->safety_check_params.enable_safety_check && isWaitingApproval()) { if (!path_decision_controller_.get_current_state().is_stable_safe) { - RCLCPP_ERROR_THROTTLE(getLogger(), *clock_, 5000, "Path is not safe against dynamic objects"); + RCLCPP_INFO_THROTTLE( + getLogger(), *clock_, 5000, + "Path is not safe against dynamic objects, so the candidate path is not approved."); return false; } } @@ -945,7 +950,8 @@ BehaviorModuleOutput GoalPlannerModule::plan() if (utils::isAllowedGoalModification(planner_data_->route_handler)) { if (!context_data_) { - RCLCPP_ERROR(getLogger(), " [pull_over] plan() is called without valid context_data"); + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 5000, " [pull_over] plan() is called without valid context_data"); } else { const auto & context_data = context_data_.value(); return planPullOver(context_data); @@ -1230,7 +1236,7 @@ void GoalPlannerModule::setOutput( if (!context_data.pull_over_path_opt) { // situation : not safe against static objects use stop_path output.path = generateStopPath(context_data); - RCLCPP_WARN_THROTTLE( + RCLCPP_INFO_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); setDrivableAreaInfo(context_data, output); return; @@ -1244,7 +1250,7 @@ void GoalPlannerModule::setOutput( // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints output.path = generateFeasibleStopPath(pull_over_path.getCurrentPath()); - RCLCPP_WARN_THROTTLE( + RCLCPP_INFO_THROTTLE( getLogger(), *clock_, 5000, "Not safe against dynamic objects, generate stop path"); debug_stop_pose_with_info_.set(std::string("feasible stop after approval")); } else { @@ -1506,7 +1512,9 @@ void GoalPlannerModule::postProcess() universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); if (!context_data_) { - RCLCPP_ERROR(getLogger(), " [pull_over] postProcess() is called without valid context_data"); + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 5000, + " [pull_over] postProcess() is called without valid context_data. use dummy context data."); } const auto context_data_dummy = PullOverContextData(true, PredictedObjects{}, PredictedObjects{}, std::nullopt, {}, {}); @@ -1544,8 +1552,10 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() if (utils::isAllowedGoalModification(planner_data_->route_handler)) { if (!context_data_) { - RCLCPP_ERROR( - getLogger(), " [pull_over] planWaitingApproval() is called without valid context_data"); + RCLCPP_WARN_THROTTLE( + getLogger(), *clock_, 5000, + " [pull_over] planWaitingApproval() is called without valid context_data. use fixed goal " + "planner"); } else { const auto & context_data = context_data_.value(); return planPullOverAsCandidate(context_data); From 53a960ea2a526de5f23839f5cd28d142d23341ac Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Thu, 5 Dec 2024 18:27:17 +0300 Subject: [PATCH 244/273] ci(pre-commit): update cpplint to 2.0.0 (#9557) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .pre-commit-config.yaml | 2 +- CPPLINT.cfg | 2 ++ .../test/test_mock_data_parser.cpp | 9 ++++--- .../test_create_vehicle_passing_areas.cpp | 2 ++ .../autoware_pure_pursuit.cpp | 4 +-- .../src/fusion_node.cpp | 26 +++++++++++-------- .../src/roi_detected_object_fusion/node.cpp | 12 ++++----- .../src/util.cpp | 6 +++++ .../src/component_monitor_node.cpp | 1 + .../reader/hdd_reader/hdd_reader.cpp | 22 ++++++++-------- 10 files changed, 51 insertions(+), 35 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index f3f3248095a0f..6e7c64fd982fc 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -76,7 +76,7 @@ repos: types_or: [c++, c, cuda] - repo: https://github.com/cpplint/cpplint - rev: 1.6.1 + rev: 2.0.0 hooks: - id: cpplint args: [--quiet] diff --git a/CPPLINT.cfg b/CPPLINT.cfg index 81869c92be64c..159042dba0b48 100644 --- a/CPPLINT.cfg +++ b/CPPLINT.cfg @@ -7,10 +7,12 @@ set noparent linelength=100 includeorder=standardcfirst filter=-build/c++11 # we do allow C++11 +filter=-build/c++17 # we allow filter=-build/namespaces_literals # we allow using namespace for literals filter=-runtime/references # we consider passing non-const references to be ok filter=-whitespace/braces # we wrap open curly braces for namespaces, classes and functions filter=-whitespace/indent # we don't indent keywords like public, protected and private with one space +filter=-whitespace/newline # we allow the developer to decide about newline at the end of file (it's clashing with clang-format) filter=-whitespace/parens # we allow closing parenthesis to be on the next line filter=-whitespace/semicolon # we allow the developer to decide about whitespace after a semicolon filter=-build/header_guard # we automatically fix the names of header guards using pre-commit diff --git a/common/autoware_test_utils/test/test_mock_data_parser.cpp b/common/autoware_test_utils/test/test_mock_data_parser.cpp index 34218d48552e9..036f16c827713 100644 --- a/common/autoware_test_utils/test/test_mock_data_parser.cpp +++ b/common/autoware_test_utils/test/test_mock_data_parser.cpp @@ -673,11 +673,12 @@ TEST(ParseFunctions, CompleteYAMLTest) // Test parsing of segments const auto segments = parse>(config["segments"]); ASSERT_EQ( - segments.size(), uint64_t(1)); // Assuming only one segment in the provided YAML for this test + segments.size(), + static_cast(1)); // Assuming only one segment in the provided YAML for this test const auto & segment0 = segments[0]; EXPECT_EQ(segment0.preferred_primitive.id, 11); - EXPECT_EQ(segment0.primitives.size(), uint64_t(2)); + EXPECT_EQ(segment0.primitives.size(), static_cast(2)); EXPECT_EQ(segment0.primitives[0].id, 22); EXPECT_EQ(segment0.primitives[0].primitive_type, "lane"); EXPECT_EQ(segment0.primitives[1].id, 33); @@ -811,10 +812,10 @@ TEST(ParseFunction, CompleteFromFilename) ASSERT_EQ( lanelet_route.segments.size(), - uint64_t(2)); // Assuming only one segment in the provided YAML for this test + static_cast(2)); // Assuming only one segment in the provided YAML for this test const auto & segment1 = lanelet_route.segments[1]; EXPECT_EQ(segment1.preferred_primitive.id, 44); - EXPECT_EQ(segment1.primitives.size(), uint64_t(4)); + EXPECT_EQ(segment1.primitives.size(), static_cast(4)); EXPECT_EQ(segment1.primitives[0].id, 55); EXPECT_EQ(segment1.primitives[0].primitive_type, "lane"); EXPECT_EQ(segment1.primitives[1].id, 66); diff --git a/control/autoware_lane_departure_checker/test/test_create_vehicle_passing_areas.cpp b/control/autoware_lane_departure_checker/test/test_create_vehicle_passing_areas.cpp index d79ebeb1e13e3..40a4db4024094 100644 --- a/control/autoware_lane_departure_checker/test/test_create_vehicle_passing_areas.cpp +++ b/control/autoware_lane_departure_checker/test/test_create_vehicle_passing_areas.cpp @@ -24,6 +24,8 @@ #include +#include + using autoware::lane_departure_checker::utils::createVehiclePassingAreas; using autoware::universe_utils::LinearRing2d; using autoware::universe_utils::Point2d; diff --git a/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/autoware_pure_pursuit.cpp b/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/autoware_pure_pursuit.cpp index ed9579f296fea..55a3680dfaaf0 100644 --- a/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/autoware_pure_pursuit.cpp +++ b/control/autoware_pure_pursuit/src/autoware_pure_pursuit_core/autoware_pure_pursuit.cpp @@ -156,9 +156,9 @@ int32_t PurePursuit::findNextPointIdx(int32_t search_start_idx) } // look for the next waypoint. - for (int32_t i = search_start_idx; i < (int32_t)curr_wps_ptr_->size(); i++) { + for (int32_t i = search_start_idx; i < static_cast(curr_wps_ptr_->size()); i++) { // if search waypoint is the last - if (i == ((int32_t)curr_wps_ptr_->size() - 1)) { + if (i == (static_cast(curr_wps_ptr_->size()) - 1)) { return i; } diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 067deb5d03a87..60406652310dd 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -215,7 +215,7 @@ void FusionNode::subCallback( preprocess(*output_msg); int64_t timestamp_nsec = - (*output_msg).header.stamp.sec * (int64_t)1e9 + (*output_msg).header.stamp.nanosec; + (*output_msg).header.stamp.sec * static_cast(1e9) + (*output_msg).header.stamp.nanosec; // if matching rois exist, fuseOnSingle // please ask maintainers before parallelize this loop because debugger is not thread safe @@ -232,14 +232,17 @@ void FusionNode::subCallback( std::list outdate_stamps; for (const auto & [k, v] : cached_roi_msgs_.at(roi_i)) { - int64_t new_stamp = timestamp_nsec + input_offset_ms_.at(roi_i) * (int64_t)1e6; - int64_t interval = abs(int64_t(k) - new_stamp); + int64_t new_stamp = timestamp_nsec + input_offset_ms_.at(roi_i) * static_cast(1e6); + int64_t interval = abs(static_cast(k) - new_stamp); - if (interval <= min_interval && interval <= match_threshold_ms_ * (int64_t)1e6) { + if ( + interval <= min_interval && interval <= match_threshold_ms_ * static_cast(1e6)) { min_interval = interval; matched_stamp = k; - } else if (int64_t(k) < new_stamp && interval > match_threshold_ms_ * (int64_t)1e6) { - outdate_stamps.push_back(int64_t(k)); + } else if ( + static_cast(k) < new_stamp && + interval > match_threshold_ms_ * static_cast(1e6)) { + outdate_stamps.push_back(static_cast(k)); } } @@ -293,7 +296,7 @@ void FusionNode::subCallback( processing_time_ms = 0; } } else { - cached_msg_.first = int64_t(timestamp_nsec); + cached_msg_.first = timestamp_nsec; cached_msg_.second = output_msg; processing_time_ms = stop_watch_ptr_->toc("processing_time", true); } @@ -305,15 +308,16 @@ void FusionNode::roiCallback( { stop_watch_ptr_->toc("processing_time", true); - int64_t timestamp_nsec = - (*input_roi_msg).header.stamp.sec * (int64_t)1e9 + (*input_roi_msg).header.stamp.nanosec; + int64_t timestamp_nsec = (*input_roi_msg).header.stamp.sec * static_cast(1e9) + + (*input_roi_msg).header.stamp.nanosec; // if cached Msg exist, try to match if (cached_msg_.second != nullptr) { - int64_t new_stamp = cached_msg_.first + input_offset_ms_.at(roi_i) * (int64_t)1e6; + int64_t new_stamp = cached_msg_.first + input_offset_ms_.at(roi_i) * static_cast(1e6); int64_t interval = abs(timestamp_nsec - new_stamp); - if (interval < match_threshold_ms_ * (int64_t)1e6 && is_fused_.at(roi_i) == false) { + if ( + interval < match_threshold_ms_ * static_cast(1e6) && is_fused_.at(roi_i) == false) { if (camera_info_map_.find(roi_i) == camera_info_map_.end()) { RCLCPP_WARN_THROTTLE( this->get_logger(), *this->get_clock(), 5000, "no camera info. id is %zu", roi_i); diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index da9d413757332..134dd7bad9129 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -69,7 +69,7 @@ void RoiDetectedObjectFusionNode::preprocess(DetectedObjects & output_msg) } int64_t timestamp_nsec = - output_msg.header.stamp.sec * (int64_t)1e9 + output_msg.header.stamp.nanosec; + output_msg.header.stamp.sec * static_cast(1e9) + output_msg.header.stamp.nanosec; passthrough_object_flags_map_.insert(std::make_pair(timestamp_nsec, passthrough_object_flags)); fused_object_flags_map_.insert(std::make_pair(timestamp_nsec, fused_object_flags)); ignored_object_flags_map_.insert(std::make_pair(timestamp_nsec, ignored_object_flags)); @@ -118,8 +118,8 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( const image_geometry::PinholeCameraModel & pinhole_camera_model) { std::map object_roi_map; - int64_t timestamp_nsec = - input_object_msg.header.stamp.sec * (int64_t)1e9 + input_object_msg.header.stamp.nanosec; + int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast(1e9) + + input_object_msg.header.stamp.nanosec; if (passthrough_object_flags_map_.size() == 0) { return object_roi_map; } @@ -205,8 +205,8 @@ void RoiDetectedObjectFusionNode::fuseObjectsOnImage( const std::vector & image_rois, const std::map & object_roi_map) { - int64_t timestamp_nsec = - input_object_msg.header.stamp.sec * (int64_t)1e9 + input_object_msg.header.stamp.nanosec; + int64_t timestamp_nsec = input_object_msg.header.stamp.sec * static_cast(1e9) + + input_object_msg.header.stamp.nanosec; if (fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) { return; } @@ -289,7 +289,7 @@ void RoiDetectedObjectFusionNode::publish(const DetectedObjects & output_msg) } int64_t timestamp_nsec = - output_msg.header.stamp.sec * (int64_t)1e9 + output_msg.header.stamp.nanosec; + output_msg.header.stamp.sec * static_cast(1e9) + output_msg.header.stamp.nanosec; if ( passthrough_object_flags_map_.size() == 0 || fused_object_flags_map_.size() == 0 || ignored_object_flags_map_.size() == 0) { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp index fde6202c7ce24..5c5aa0a26b3b4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/util.cpp @@ -22,6 +22,12 @@ #include +#include +#include +#include +#include +#include + namespace autoware::behavior_velocity_planner { diff --git a/system/autoware_component_monitor/src/component_monitor_node.cpp b/system/autoware_component_monitor/src/component_monitor_node.cpp index 3c5d6b6667725..ab234f7fd66f2 100644 --- a/system/autoware_component_monitor/src/component_monitor_node.cpp +++ b/system/autoware_component_monitor/src/component_monitor_node.cpp @@ -147,6 +147,7 @@ std::uint64_t ComponentMonitor::parse_memory_res(const std::string & mem_res) { // example 1: 12.3g // example 2: 123 (without suffix, just bytes) + // NOLINTNEXTLINE(readability/casting) static const std::unordered_map> unit_map{ {'k', unit_conversions::kib_to_bytes}, {'m', unit_conversions::mib_to_bytes}, {'g', unit_conversions::gib_to_bytes}, {'t', unit_conversions::tib_to_bytes}, diff --git a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp b/system/system_monitor/reader/hdd_reader/hdd_reader.cpp index 589f9a3970098..740f841382f47 100644 --- a/system/system_monitor/reader/hdd_reader/hdd_reader.cpp +++ b/system/system_monitor/reader/hdd_reader/hdd_reader.cpp @@ -330,10 +330,10 @@ int get_nvme_identify(int fd, HddInfo * info) char data[4096]{}; // Fixed size for Identify command // The Identify command returns a data buffer that describes information about the NVM subsystem - cmd.opcode = 0x06; // Identify - cmd.addr = (uint64_t)data; // memory address of data - cmd.data_len = sizeof(data); // length of data - cmd.cdw10 = 0x01; // Identify Controller data structure + cmd.opcode = 0x06; // Identify + cmd.addr = reinterpret_cast(data); // memory address of data + cmd.data_len = sizeof(data); // length of data + cmd.cdw10 = 0x01; // Identify Controller data structure // send Admin Command to device int ret = ioctl(fd, NVME_IOCTL_ADMIN_CMD, &cmd); @@ -368,13 +368,13 @@ int get_nvme_smart_data(int fd, HddInfo * info) unsigned char data[144]{}; // 36 Dword (get byte 0 to 143) // The Get Log Page command returns a data buffer containing the log page requested - cmd.opcode = 0x02; // Get Log Page - cmd.nsid = 0xFFFFFFFF; // Global log page - cmd.addr = (uint64_t)data; // memory address of data - cmd.data_len = sizeof(data); // length of data - cmd.cdw10 = 0x00240002; // Bit 27:16 Number of Dwords (NUMD) = 024h (36 Dword) - // - Minimum necessary size to obtain S.M.A.R.T. informations - // Bit 07:00 = 02h (SMART / Health Information) + cmd.opcode = 0x02; // Get Log Page + cmd.nsid = 0xFFFFFFFF; // Global log page + cmd.addr = reinterpret_cast(data); // memory address of data + cmd.data_len = sizeof(data); // length of data + cmd.cdw10 = 0x00240002; // Bit 27:16 Number of Dwords (NUMD) = 024h (36 Dword) + // - Minimum necessary size to obtain S.M.A.R.T. informations + // Bit 07:00 = 02h (SMART / Health Information) // send Admin Command to device int ret = ioctl(fd, NVME_IOCTL_ADMIN_CMD, &cmd); From 8cf0bc970d83f342d78e8c4d16ffaf0380782c9c Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Fri, 6 Dec 2024 01:05:25 +0900 Subject: [PATCH 245/273] feat(autoware_geography_utils)!: move autoware_geography_utils to autoware.core (#9554) Signed-off-by: Ryohsuke Mitsudome --- common/autoware_geography_utils/CHANGELOG.rst | 15 -- .../autoware_geography_utils/CMakeLists.txt | 37 ---- common/autoware_geography_utils/README.md | 5 - .../autoware/geography_utils/height.hpp | 33 ---- .../geography_utils/lanelet2_projector.hpp | 32 ---- .../autoware/geography_utils/projection.hpp | 33 ---- common/autoware_geography_utils/package.xml | 33 ---- .../autoware_geography_utils/src/height.cpp | 63 ------- .../src/lanelet2_projector.cpp | 57 ------- .../src/projection.cpp | 97 ----------- .../test/test_geography_utils.cpp | 26 --- .../test/test_height.cpp | 86 ---------- .../test/test_projection.cpp | 161 ------------------ 13 files changed, 678 deletions(-) delete mode 100644 common/autoware_geography_utils/CHANGELOG.rst delete mode 100644 common/autoware_geography_utils/CMakeLists.txt delete mode 100644 common/autoware_geography_utils/README.md delete mode 100644 common/autoware_geography_utils/include/autoware/geography_utils/height.hpp delete mode 100644 common/autoware_geography_utils/include/autoware/geography_utils/lanelet2_projector.hpp delete mode 100644 common/autoware_geography_utils/include/autoware/geography_utils/projection.hpp delete mode 100644 common/autoware_geography_utils/package.xml delete mode 100644 common/autoware_geography_utils/src/height.cpp delete mode 100644 common/autoware_geography_utils/src/lanelet2_projector.cpp delete mode 100644 common/autoware_geography_utils/src/projection.cpp delete mode 100644 common/autoware_geography_utils/test/test_geography_utils.cpp delete mode 100644 common/autoware_geography_utils/test/test_height.cpp delete mode 100644 common/autoware_geography_utils/test/test_projection.cpp diff --git a/common/autoware_geography_utils/CHANGELOG.rst b/common/autoware_geography_utils/CHANGELOG.rst deleted file mode 100644 index 623861bbd01c3..0000000000000 --- a/common/autoware_geography_utils/CHANGELOG.rst +++ /dev/null @@ -1,15 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package autoware_geography_utils -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -0.38.0 (2024-11-08) -------------------- -* unify package.xml version to 0.37.0 -* refactor(geography_utils): prefix package and namespace with autoware (`#7790 `_) - * refactor(geography_utils): prefix package and namespace with autoware - * move headers to include/autoware/ - --------- -* Contributors: Esteve Fernandez, Yutaka Kondo - -0.26.0 (2024-04-03) -------------------- diff --git a/common/autoware_geography_utils/CMakeLists.txt b/common/autoware_geography_utils/CMakeLists.txt deleted file mode 100644 index b4ab5c2f74494..0000000000000 --- a/common/autoware_geography_utils/CMakeLists.txt +++ /dev/null @@ -1,37 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(autoware_geography_utils) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -# GeographicLib -find_package(PkgConfig) -find_path(GeographicLib_INCLUDE_DIR GeographicLib/Config.h - PATH_SUFFIXES GeographicLib -) -set(GeographicLib_INCLUDE_DIRS ${GeographicLib_INCLUDE_DIR}) -find_library(GeographicLib_LIBRARIES NAMES Geographic) - -ament_auto_add_library(${PROJECT_NAME} SHARED - src/height.cpp - src/projection.cpp - src/lanelet2_projector.cpp -) - -target_link_libraries(${PROJECT_NAME} - ${GeographicLib_LIBRARIES} -) - -if(BUILD_TESTING) - find_package(ament_cmake_ros REQUIRED) - - file(GLOB_RECURSE test_files test/*.cpp) - - ament_add_ros_isolated_gtest(test_${PROJECT_NAME} ${test_files}) - - target_link_libraries(test_${PROJECT_NAME} - ${PROJECT_NAME} - ) -endif() - -ament_auto_package() diff --git a/common/autoware_geography_utils/README.md b/common/autoware_geography_utils/README.md deleted file mode 100644 index fb4c2dc3a8312..0000000000000 --- a/common/autoware_geography_utils/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# geography_utils - -## Purpose - -This package contains geography-related functions used by other packages, so please refer to them as needed. diff --git a/common/autoware_geography_utils/include/autoware/geography_utils/height.hpp b/common/autoware_geography_utils/include/autoware/geography_utils/height.hpp deleted file mode 100644 index 1f205eb8f8b18..0000000000000 --- a/common/autoware_geography_utils/include/autoware/geography_utils/height.hpp +++ /dev/null @@ -1,33 +0,0 @@ -// Copyright 2023 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__GEOGRAPHY_UTILS__HEIGHT_HPP_ -#define AUTOWARE__GEOGRAPHY_UTILS__HEIGHT_HPP_ - -#include - -namespace autoware::geography_utils -{ - -typedef double (*HeightConversionFunction)( - const double height, const double latitude, const double longitude); -double convert_wgs84_to_egm2008(const double height, const double latitude, const double longitude); -double convert_egm2008_to_wgs84(const double height, const double latitude, const double longitude); -double convert_height( - const double height, const double latitude, const double longitude, - const std::string & source_vertical_datum, const std::string & target_vertical_datum); - -} // namespace autoware::geography_utils - -#endif // AUTOWARE__GEOGRAPHY_UTILS__HEIGHT_HPP_ diff --git a/common/autoware_geography_utils/include/autoware/geography_utils/lanelet2_projector.hpp b/common/autoware_geography_utils/include/autoware/geography_utils/lanelet2_projector.hpp deleted file mode 100644 index 0eea2a9ff7fbb..0000000000000 --- a/common/autoware_geography_utils/include/autoware/geography_utils/lanelet2_projector.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// Copyright 2023 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__GEOGRAPHY_UTILS__LANELET2_PROJECTOR_HPP_ -#define AUTOWARE__GEOGRAPHY_UTILS__LANELET2_PROJECTOR_HPP_ - -#include - -#include - -#include - -namespace autoware::geography_utils -{ -using MapProjectorInfo = autoware_map_msgs::msg::MapProjectorInfo; - -std::unique_ptr get_lanelet2_projector(const MapProjectorInfo & projector_info); - -} // namespace autoware::geography_utils - -#endif // AUTOWARE__GEOGRAPHY_UTILS__LANELET2_PROJECTOR_HPP_ diff --git a/common/autoware_geography_utils/include/autoware/geography_utils/projection.hpp b/common/autoware_geography_utils/include/autoware/geography_utils/projection.hpp deleted file mode 100644 index 5c4a69b15e192..0000000000000 --- a/common/autoware_geography_utils/include/autoware/geography_utils/projection.hpp +++ /dev/null @@ -1,33 +0,0 @@ -// Copyright 2023 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__GEOGRAPHY_UTILS__PROJECTION_HPP_ -#define AUTOWARE__GEOGRAPHY_UTILS__PROJECTION_HPP_ - -#include -#include -#include - -namespace autoware::geography_utils -{ -using MapProjectorInfo = autoware_map_msgs::msg::MapProjectorInfo; -using GeoPoint = geographic_msgs::msg::GeoPoint; -using LocalPoint = geometry_msgs::msg::Point; - -LocalPoint project_forward(const GeoPoint & geo_point, const MapProjectorInfo & projector_info); -GeoPoint project_reverse(const LocalPoint & local_point, const MapProjectorInfo & projector_info); - -} // namespace autoware::geography_utils - -#endif // AUTOWARE__GEOGRAPHY_UTILS__PROJECTION_HPP_ diff --git a/common/autoware_geography_utils/package.xml b/common/autoware_geography_utils/package.xml deleted file mode 100644 index 8777bf4c13d45..0000000000000 --- a/common/autoware_geography_utils/package.xml +++ /dev/null @@ -1,33 +0,0 @@ - - - - autoware_geography_utils - 0.38.0 - The autoware_geography_utils package - Yamato Ando - Masahiro Sakamoto - NGUYEN Viet Anh - Taiki Yamada - Shintaro Sakoda - Ryu Yamamoto - Apache License 2.0 - Koji Minoda - - ament_cmake_auto - autoware_cmake - - autoware_lanelet2_extension - autoware_map_msgs - geographic_msgs - geographiclib - geometry_msgs - lanelet2_io - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/common/autoware_geography_utils/src/height.cpp b/common/autoware_geography_utils/src/height.cpp deleted file mode 100644 index 745dbf5b22cfc..0000000000000 --- a/common/autoware_geography_utils/src/height.cpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright 2023 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 - -#include -#include -#include -#include - -namespace autoware::geography_utils -{ - -double convert_wgs84_to_egm2008(const double height, const double latitude, const double longitude) -{ - GeographicLib::Geoid egm2008("egm2008-1"); - // cSpell: ignore ELLIPSOIDTOGEOID - return egm2008.ConvertHeight(latitude, longitude, height, GeographicLib::Geoid::ELLIPSOIDTOGEOID); -} - -double convert_egm2008_to_wgs84(const double height, const double latitude, const double longitude) -{ - GeographicLib::Geoid egm2008("egm2008-1"); - // cSpell: ignore GEOIDTOELLIPSOID - return egm2008.ConvertHeight(latitude, longitude, height, GeographicLib::Geoid::GEOIDTOELLIPSOID); -} - -double convert_height( - const double height, const double latitude, const double longitude, - const std::string & source_vertical_datum, const std::string & target_vertical_datum) -{ - if (source_vertical_datum == target_vertical_datum) { - return height; - } - std::map, HeightConversionFunction> conversion_map; - conversion_map[{"WGS84", "EGM2008"}] = convert_wgs84_to_egm2008; - conversion_map[{"EGM2008", "WGS84"}] = convert_egm2008_to_wgs84; - - auto key = std::make_pair(source_vertical_datum, target_vertical_datum); - if (conversion_map.find(key) != conversion_map.end()) { - return conversion_map[key](height, latitude, longitude); - } else { - std::string error_message = - "Invalid conversion types: " + std::string(source_vertical_datum.c_str()) + " to " + - std::string(target_vertical_datum.c_str()); - - throw std::invalid_argument(error_message); - } -} - -} // namespace autoware::geography_utils diff --git a/common/autoware_geography_utils/src/lanelet2_projector.cpp b/common/autoware_geography_utils/src/lanelet2_projector.cpp deleted file mode 100644 index 76c69a85ae0bc..0000000000000 --- a/common/autoware_geography_utils/src/lanelet2_projector.cpp +++ /dev/null @@ -1,57 +0,0 @@ -// Copyright 2023 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 -#include -#include - -#include - -#include -#include - -namespace autoware::geography_utils -{ - -std::unique_ptr get_lanelet2_projector(const MapProjectorInfo & projector_info) -{ - if (projector_info.projector_type == MapProjectorInfo::LOCAL_CARTESIAN_UTM) { - lanelet::GPSPoint position{ - projector_info.map_origin.latitude, projector_info.map_origin.longitude, - projector_info.map_origin.altitude}; - lanelet::Origin origin{position}; - lanelet::projection::UtmProjector projector{origin}; - return std::make_unique(projector); - - } else if (projector_info.projector_type == MapProjectorInfo::MGRS) { - lanelet::projection::MGRSProjector projector{}; - projector.setMGRSCode(projector_info.mgrs_grid); - return std::make_unique(projector); - - } else if (projector_info.projector_type == MapProjectorInfo::TRANSVERSE_MERCATOR) { - lanelet::GPSPoint position{ - projector_info.map_origin.latitude, projector_info.map_origin.longitude, - projector_info.map_origin.altitude}; - lanelet::Origin origin{position}; - lanelet::projection::TransverseMercatorProjector projector{origin}; - return std::make_unique(projector); - } - const std::string error_msg = - "Invalid map projector type: " + projector_info.projector_type + - ". Currently supported types: MGRS, LocalCartesianUTM, and TransverseMercator"; - throw std::invalid_argument(error_msg); -} - -} // namespace autoware::geography_utils diff --git a/common/autoware_geography_utils/src/projection.cpp b/common/autoware_geography_utils/src/projection.cpp deleted file mode 100644 index e113c8da7b519..0000000000000 --- a/common/autoware_geography_utils/src/projection.cpp +++ /dev/null @@ -1,97 +0,0 @@ -// Copyright 2023 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 -#include -#include - -#include - -namespace autoware::geography_utils -{ - -Eigen::Vector3d to_basic_point_3d_pt(const LocalPoint src) -{ - Eigen::Vector3d dst; - dst.x() = src.x; - dst.y() = src.y; - dst.z() = src.z; - return dst; -} - -LocalPoint project_forward(const GeoPoint & geo_point, const MapProjectorInfo & projector_info) -{ - std::unique_ptr projector = get_lanelet2_projector(projector_info); - lanelet::GPSPoint position{geo_point.latitude, geo_point.longitude, geo_point.altitude}; - - lanelet::BasicPoint3d projected_local_point; - if (projector_info.projector_type == MapProjectorInfo::MGRS) { - const int mgrs_precision = 9; // set precision as 100 micro meter - const auto mgrs_projector = dynamic_cast(projector.get()); - - // project x and y using projector - // note that the altitude is ignored in MGRS projection conventionally - projected_local_point = mgrs_projector->forward(position, mgrs_precision); - } else { - // project x and y using projector - // note that the original projector such as UTM projector does not compensate for the altitude - // offset - projected_local_point = projector->forward(position); - - // correct z based on the map origin - // note that the converted altitude in local point is in the same vertical datum as the geo - // point - projected_local_point.z() = geo_point.altitude - projector_info.map_origin.altitude; - } - - LocalPoint local_point; - local_point.x = projected_local_point.x(); - local_point.y = projected_local_point.y(); - local_point.z = projected_local_point.z(); - - return local_point; -} - -GeoPoint project_reverse(const LocalPoint & local_point, const MapProjectorInfo & projector_info) -{ - std::unique_ptr projector = get_lanelet2_projector(projector_info); - - lanelet::GPSPoint projected_gps_point; - if (projector_info.projector_type == MapProjectorInfo::MGRS) { - const auto mgrs_projector = dynamic_cast(projector.get()); - // project latitude and longitude using projector - // note that the z is ignored in MGRS projection conventionally - projected_gps_point = - mgrs_projector->reverse(to_basic_point_3d_pt(local_point), projector_info.mgrs_grid); - } else { - // project latitude and longitude using projector - // note that the original projector such as UTM projector does not compensate for the altitude - // offset - projected_gps_point = projector->reverse(to_basic_point_3d_pt(local_point)); - - // correct altitude based on the map origin - // note that the converted altitude in local point is in the same vertical datum as the geo - // point - projected_gps_point.ele = local_point.z + projector_info.map_origin.altitude; - } - - GeoPoint geo_point; - geo_point.latitude = projected_gps_point.lat; - geo_point.longitude = projected_gps_point.lon; - geo_point.altitude = projected_gps_point.ele; - return geo_point; -} - -} // namespace autoware::geography_utils diff --git a/common/autoware_geography_utils/test/test_geography_utils.cpp b/common/autoware_geography_utils/test/test_geography_utils.cpp deleted file mode 100644 index ee0e7428db2f2..0000000000000 --- a/common/autoware_geography_utils/test/test_geography_utils.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright 2023 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/geography_utils/height.hpp" -#include "autoware/geography_utils/lanelet2_projector.hpp" -#include "autoware/geography_utils/projection.hpp" - -#include - -int main(int argc, char * argv[]) -{ - testing::InitGoogleTest(&argc, argv); - bool result = RUN_ALL_TESTS(); - return result; -} diff --git a/common/autoware_geography_utils/test/test_height.cpp b/common/autoware_geography_utils/test/test_height.cpp deleted file mode 100644 index f624f6c3ff9e3..0000000000000 --- a/common/autoware_geography_utils/test/test_height.cpp +++ /dev/null @@ -1,86 +0,0 @@ -// Copyright 2023 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 - -#include -#include - -// Test case to verify if same source and target datums return original height -TEST(GeographyUtils, SameSourceTargetDatum) -{ - const double height = 10.0; - const double latitude = 35.0; - const double longitude = 139.0; - const std::string datum = "WGS84"; - - double converted_height = - autoware::geography_utils::convert_height(height, latitude, longitude, datum, datum); - - EXPECT_DOUBLE_EQ(height, converted_height); -} - -// Test case to verify valid source and target datums -TEST(GeographyUtils, ValidSourceTargetDatum) -{ - // Calculated with - // https://www.unavco.org/software/geodetic-utilities/geoid-height-calculator/geoid-height-calculator.html - const double height = 10.0; - const double latitude = 35.0; - const double longitude = 139.0; - const double target_height = -30.18; - - double converted_height = - autoware::geography_utils::convert_height(height, latitude, longitude, "WGS84", "EGM2008"); - - EXPECT_NEAR(target_height, converted_height, 0.1); -} - -// Test case to verify invalid source and target datums -TEST(GeographyUtils, InvalidSourceTargetDatum) -{ - const double height = 10.0; - const double latitude = 35.0; - const double longitude = 139.0; - - EXPECT_THROW( - autoware::geography_utils::convert_height(height, latitude, longitude, "INVALID1", "INVALID2"), - std::invalid_argument); -} - -// Test case to verify invalid source datums -TEST(GeographyUtils, InvalidSourceDatum) -{ - const double height = 10.0; - const double latitude = 35.0; - const double longitude = 139.0; - - EXPECT_THROW( - autoware::geography_utils::convert_height(height, latitude, longitude, "INVALID1", "WGS84"), - std::invalid_argument); -} - -// Test case to verify invalid target datums -TEST(GeographyUtils, InvalidTargetDatum) -{ - const double height = 10.0; - const double latitude = 35.0; - const double longitude = 139.0; - - EXPECT_THROW( - autoware::geography_utils::convert_height(height, latitude, longitude, "WGS84", "INVALID2"), - std::invalid_argument); -} diff --git a/common/autoware_geography_utils/test/test_projection.cpp b/common/autoware_geography_utils/test/test_projection.cpp deleted file mode 100644 index b8d036c136eeb..0000000000000 --- a/common/autoware_geography_utils/test/test_projection.cpp +++ /dev/null @@ -1,161 +0,0 @@ -// Copyright 2023 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 - -#include -#include - -TEST(GeographyUtilsProjection, ProjectForwardToMGRS) -{ - // source point - geographic_msgs::msg::GeoPoint geo_point; - geo_point.latitude = 35.62426; - geo_point.longitude = 139.74252; - geo_point.altitude = 10.0; - - // target point - geometry_msgs::msg::Point local_point; - local_point.x = 86128.0; - local_point.y = 43002.0; - local_point.z = 10.0; - - // projector info - autoware_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::MGRS; - projector_info.mgrs_grid = "54SUE"; - projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; - - // conversion - const geometry_msgs::msg::Point converted_point = - autoware::geography_utils::project_forward(geo_point, projector_info); - - EXPECT_NEAR(converted_point.x, local_point.x, 1.0); - EXPECT_NEAR(converted_point.y, local_point.y, 1.0); - EXPECT_NEAR(converted_point.z, local_point.z, 1.0); -} - -TEST(GeographyUtilsProjection, ProjectReverseFromMGRS) -{ - // source point - geometry_msgs::msg::Point local_point; - local_point.x = 86128.0; - local_point.y = 43002.0; - local_point.z = 10.0; - - // target point - geographic_msgs::msg::GeoPoint geo_point; - geo_point.latitude = 35.62426; - geo_point.longitude = 139.74252; - geo_point.altitude = 10.0; - - // projector info - autoware_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::MGRS; - projector_info.mgrs_grid = "54SUE"; - projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; - - // conversion - const geographic_msgs::msg::GeoPoint converted_point = - autoware::geography_utils::project_reverse(local_point, projector_info); - - EXPECT_NEAR(converted_point.latitude, geo_point.latitude, 0.0001); - EXPECT_NEAR(converted_point.longitude, geo_point.longitude, 0.0001); - EXPECT_NEAR(converted_point.altitude, geo_point.altitude, 0.0001); -} - -TEST(GeographyUtilsProjection, ProjectForwardAndReverseMGRS) -{ - // source point - geographic_msgs::msg::GeoPoint geo_point; - geo_point.latitude = 35.62426; - geo_point.longitude = 139.74252; - geo_point.altitude = 10.0; - - // projector info - autoware_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::MGRS; - projector_info.mgrs_grid = "54SUE"; - projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; - - // conversion - const geometry_msgs::msg::Point converted_local_point = - autoware::geography_utils::project_forward(geo_point, projector_info); - const geographic_msgs::msg::GeoPoint converted_geo_point = - autoware::geography_utils::project_reverse(converted_local_point, projector_info); - - EXPECT_NEAR(converted_geo_point.latitude, geo_point.latitude, 0.0001); - EXPECT_NEAR(converted_geo_point.longitude, geo_point.longitude, 0.0001); - EXPECT_NEAR(converted_geo_point.altitude, geo_point.altitude, 0.0001); -} - -TEST(GeographyUtilsProjection, ProjectForwardToLocalCartesianUTMOrigin) -{ - // source point - geographic_msgs::msg::GeoPoint geo_point; - geo_point.latitude = 35.62406; - geo_point.longitude = 139.74252; - geo_point.altitude = 10.0; - - // target point - geometry_msgs::msg::Point local_point; - local_point.x = 0.0; - local_point.y = -22.18; - local_point.z = 20.0; - - // projector info - autoware_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM; - projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; - projector_info.map_origin.latitude = 35.62426; - projector_info.map_origin.longitude = 139.74252; - projector_info.map_origin.altitude = -10.0; - - // conversion - const geometry_msgs::msg::Point converted_point = - autoware::geography_utils::project_forward(geo_point, projector_info); - - EXPECT_NEAR(converted_point.x, local_point.x, 1.0); - EXPECT_NEAR(converted_point.y, local_point.y, 1.0); - EXPECT_NEAR(converted_point.z, local_point.z, 1.0); -} - -TEST(GeographyUtilsProjection, ProjectForwardAndReverseLocalCartesianUTMOrigin) -{ - // source point - geographic_msgs::msg::GeoPoint geo_point; - geo_point.latitude = 35.62426; - geo_point.longitude = 139.74252; - geo_point.altitude = 10.0; - - // projector info - autoware_map_msgs::msg::MapProjectorInfo projector_info; - projector_info.projector_type = autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM; - projector_info.vertical_datum = autoware_map_msgs::msg::MapProjectorInfo::WGS84; - projector_info.map_origin.latitude = 35.0; - projector_info.map_origin.longitude = 139.0; - projector_info.map_origin.altitude = 0.0; - - // conversion - const geometry_msgs::msg::Point converted_local_point = - autoware::geography_utils::project_forward(geo_point, projector_info); - const geographic_msgs::msg::GeoPoint converted_geo_point = - autoware::geography_utils::project_reverse(converted_local_point, projector_info); - - EXPECT_NEAR(converted_geo_point.latitude, geo_point.latitude, 0.0001); - EXPECT_NEAR(converted_geo_point.longitude, geo_point.longitude, 0.0001); - EXPECT_NEAR(converted_geo_point.altitude, geo_point.altitude, 0.0001); -} From 63cfff8419e62c4e9cb1df2edb439b9324b89629 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Fri, 6 Dec 2024 07:31:46 +0900 Subject: [PATCH 246/273] test(autoware_behavior_velocity_planner_common): refactor and test autoware_behavior_velocity_planner_common (#9551) * test(autoware_behavior_velocity_planner_common): refactor and test autoware_behavior_velocity_planner_common Signed-off-by: Y.Hisaki * remove nodiscard Signed-off-by: Y.Hisaki * update Signed-off-by: Y.Hisaki * fix Signed-off-by: Y.Hisaki * fix * update Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../CMakeLists.txt | 8 +- .../planner_data.hpp | 82 +---- .../scene_module_interface.hpp | 6 +- .../utilization/arc_lane_util.hpp | 8 +- .../utilization/debug.hpp | 8 +- .../utilization/path_utilization.hpp | 4 +- .../utilization/state_machine.hpp | 7 +- .../utilization/util.hpp | 46 ++- .../package.xml | 1 + .../src/planner_data.cpp | 72 ++++ .../src/utilization/arc_lane_util.cpp | 9 - .../src/utilization/boost_geometry_helper.cpp | 10 +- .../src/utilization/debug.cpp | 33 +- .../src/utilization/path_utilization.cpp | 9 +- .../src/utilization/trajectory_utils.cpp | 6 +- .../src/utilization/util.cpp | 83 +++-- ...lization.cpp => test_path_utilization.cpp} | 67 ++++ .../test/src/test_trajectory_utils.cpp | 113 +++++++ .../test/src/test_util.cpp | 308 ++++++++++++++++++ 19 files changed, 680 insertions(+), 200 deletions(-) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/planner_data.cpp rename planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/{test_utilization.cpp => test_path_utilization.cpp} (70%) create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_trajectory_utils.cpp create mode 100644 planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_util.cpp diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CMakeLists.txt b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CMakeLists.txt index f76fcfa31c240..4c06c427a026d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CMakeLists.txt +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CMakeLists.txt @@ -6,6 +6,7 @@ autoware_package() ament_auto_add_library(${PROJECT_NAME} SHARED src/scene_module_interface.cpp + src/planner_data.cpp src/utilization/path_utilization.cpp src/utilization/trajectory_utils.cpp src/utilization/arc_lane_util.cpp @@ -15,11 +16,8 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) if(BUILD_TESTING) - ament_add_ros_isolated_gtest(test_${PROJECT_NAME} - test/src/test_state_machine.cpp - test/src/test_arc_lane_util.cpp - test/src/test_utilization.cpp - ) + file(GLOB TEST_SOURCES test/src/*.cpp) + ament_add_ros_isolated_gtest(test_${PROJECT_NAME} ${TEST_SOURCES}) target_link_libraries(test_${PROJECT_NAME} gtest_main ${PROJECT_NAME} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp index 4075f356c187a..309ba33a3498a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/planner_data.hpp @@ -15,11 +15,10 @@ #ifndef AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ #define AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ +#include "autoware/behavior_velocity_planner_common/utilization/util.hpp" #include "autoware/route_handler/route_handler.hpp" - -#include -#include -#include +#include "autoware/velocity_smoother/smoother/smoother_base.hpp" +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include #include @@ -38,32 +37,19 @@ #include #include -#include #include #include #include #include -#include namespace autoware::behavior_velocity_planner { -class BehaviorVelocityPlannerNode; struct PlannerData { - explicit PlannerData(rclcpp::Node & node) - : clock_(node.get_clock()), - vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()) - { - max_stop_acceleration_threshold = node.declare_parameter( - "max_accel"); // TODO(someone): read min_acc in velocity_controller.param.yaml? - max_stop_jerk_threshold = node.declare_parameter("max_jerk"); - system_delay = node.declare_parameter("system_delay"); - delay_response_time = node.declare_parameter("delay_response_time"); - } + explicit PlannerData(rclcpp::Node & node); rclcpp::Clock::SharedPtr clock_; - // msgs from callbacks that are used for data-ready geometry_msgs::msg::PoseStamped::ConstSharedPtr current_odometry; geometry_msgs::msg::TwistStamped::ConstSharedPtr current_velocity; geometry_msgs::msg::AccelWithCovarianceStamped::ConstSharedPtr current_acceleration; @@ -71,85 +57,33 @@ struct PlannerData std::deque velocity_buffer; autoware_perception_msgs::msg::PredictedObjects::ConstSharedPtr predicted_objects; pcl::PointCloud::ConstPtr no_ground_pointcloud; - // occupancy grid + nav_msgs::msg::OccupancyGrid::ConstSharedPtr occupancy_grid; - // nearest search double ego_nearest_dist_threshold; double ego_nearest_yaw_threshold; - // other internal data - // traffic_light_id_map_raw is the raw observation, while traffic_light_id_map_keep_last keeps the - // last observed infomation for UNKNOWN std::map traffic_light_id_map_raw_; std::map traffic_light_id_map_last_observed_; std::optional external_velocity_limit; tier4_v2x_msgs::msg::VirtualTrafficLightStateArray::ConstSharedPtr virtual_traffic_light_states; - // This variable is used when the Autoware's behavior has to depend on whether it's simulation or - // not. bool is_simulation = false; - // velocity smoother std::shared_ptr velocity_smoother_; - // route handler std::shared_ptr route_handler_; - // parameters autoware::vehicle_info_utils::VehicleInfo vehicle_info_; - // additional parameters double max_stop_acceleration_threshold; double max_stop_jerk_threshold; double system_delay; double delay_response_time; double stop_line_extend_length; - bool isVehicleStopped(const double stop_duration = 0.0) const - { - if (velocity_buffer.empty()) { - return false; - } - - // Get velocities within stop_duration - const auto now = clock_->now(); - std::vector vs; - for (const auto & velocity : velocity_buffer) { - vs.push_back(velocity.twist.linear.x); - - const auto & s = velocity.header.stamp; - const auto time_diff = - now >= s ? now - s : rclcpp::Duration(0, 0); // Note: negative time throws an exception. - if (time_diff.seconds() >= stop_duration) { - break; - } - } - - // Check all velocities - constexpr double stop_velocity = 1e-3; - for (const auto & v : vs) { - if (v >= stop_velocity) { - return false; - } - } - - return true; - } - - /** - *@fn - *@brief queries the traffic signal information of given Id. if keep_last_observation = true, - *recent UNKNOWN observation is overwritten as the last non-UNKNOWN observation - */ + bool isVehicleStopped(const double stop_duration = 0.0) const; + std::optional getTrafficSignal( - const lanelet::Id id, const bool keep_last_observation = false) const - { - const auto & traffic_light_id_map = - keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_; - if (traffic_light_id_map.count(id) == 0) { - return std::nullopt; - } - return std::make_optional(traffic_light_id_map.at(id)); - } + const lanelet::Id id, const bool keep_last_observation = false) const; }; } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp index 5725ebe51b4a5..fadda66f12562 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp @@ -39,6 +39,7 @@ #include #include #include +#include #include // Debug @@ -69,9 +70,9 @@ struct ObjectOfInterest autoware_perception_msgs::msg::Shape shape; ColorName color; ObjectOfInterest( - const geometry_msgs::msg::Pose & pose, const autoware_perception_msgs::msg::Shape & shape, + const geometry_msgs::msg::Pose & pose, autoware_perception_msgs::msg::Shape shape, const ColorName & color_name) - : pose(pose), shape(shape), color(color_name) + : pose(pose), shape(std::move(shape)), color(color_name) { } }; @@ -89,6 +90,7 @@ class SceneModuleInterface virtual std::vector createVirtualWalls() = 0; int64_t getModuleId() const { return module_id_; } + void setPlannerData(const std::shared_ptr & planner_data) { planner_data_ = planner_data; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp index 56154879ea938..fae13db2822e7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/arc_lane_util.hpp @@ -20,7 +20,6 @@ #include -#include #include #include @@ -29,9 +28,8 @@ namespace autoware::behavior_velocity_planner { -namespace -{ -geometry_msgs::msg::Point convertToGeomPoint(const autoware::universe_utils::Point2d & p) + +inline geometry_msgs::msg::Point convertToGeomPoint(const autoware::universe_utils::Point2d & p) { geometry_msgs::msg::Point geom_p; geom_p.x = p.x(); @@ -40,8 +38,6 @@ geometry_msgs::msg::Point convertToGeomPoint(const autoware::universe_utils::Poi return geom_p; } -} // namespace - namespace arc_lane_utils { using PathIndexWithPose = std::pair; // front index, pose diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/debug.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/debug.hpp index 3a1c8fdeb7a0d..5ac91cdaf1369 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/debug.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/debug.hpp @@ -26,9 +26,7 @@ #include #include -namespace autoware::behavior_velocity_planner -{ -namespace debug +namespace autoware::behavior_velocity_planner::debug { visualization_msgs::msg::MarkerArray createPolygonMarkerArray( const geometry_msgs::msg::Polygon & polygon, const std::string & ns, const int64_t module_id, @@ -46,6 +44,6 @@ visualization_msgs::msg::MarkerArray createPointsMarkerArray( const std::vector & points, const std::string & ns, const int64_t module_id, const rclcpp::Time & now, const double x, const double y, const double z, const double r, const double g, const double b); -} // namespace debug -} // namespace autoware::behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner::debug + #endif // AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__DEBUG_HPP_ diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/path_utilization.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/path_utilization.hpp index 1e45e5655f12f..2d4dab018fb18 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/path_utilization.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/path_utilization.hpp @@ -20,13 +20,11 @@ #include #include -#include - namespace autoware::behavior_velocity_planner { bool splineInterpolate( const tier4_planning_msgs::msg::PathWithLaneId & input, const double interval, - tier4_planning_msgs::msg::PathWithLaneId & output, const rclcpp::Logger logger); + tier4_planning_msgs::msg::PathWithLaneId & output, const rclcpp::Logger & logger); autoware_planning_msgs::msg::Path interpolatePath( const autoware_planning_msgs::msg::Path & path, const double length, const double interval); autoware_planning_msgs::msg::Path filterLitterPathPoint( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/state_machine.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/state_machine.hpp index 4d88f2bfecce8..dfe70d376621e 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/state_machine.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/state_machine.hpp @@ -19,7 +19,6 @@ #include #include -#include namespace autoware::behavior_velocity_planner { @@ -37,11 +36,11 @@ class StateMachine { if (state == State::STOP) { return "STOP"; - } else if (state == State::GO) { + } + if (state == State::GO) { return "GO"; - } else { - return ""; } + return ""; } StateMachine() { diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp index 4cbf820268df5..fc4f852ef82f7 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/utilization/util.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__UTIL_HPP_ #define AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__UTILIZATION__UTIL_HPP_ -#include +#include "autoware/universe_utils/geometry/boost_geometry.hpp" #include #include @@ -36,23 +36,29 @@ namespace autoware::behavior_velocity_planner { +/** + * @brief Represents detection range parameters. + */ struct DetectionRange { - bool use_right = true; - bool use_left = true; - double interval; - double min_longitudinal_distance; - double max_longitudinal_distance; - double max_lateral_distance; - double wheel_tread; - double right_overhang; - double left_overhang; + bool use_right = true; ///< Whether to use the right side. + bool use_left = true; ///< Whether to use the left side. + double interval{0.0}; ///< Interval of detection points. + double min_longitudinal_distance{0.0}; ///< Minimum longitudinal detection distance. + double max_longitudinal_distance{0.0}; ///< Maximum longitudinal detection distance. + double max_lateral_distance{0.0}; ///< Maximum lateral detection distance. + double wheel_tread{0.0}; ///< Wheel tread of the vehicle. + double right_overhang{0.0}; ///< Right overhang of the vehicle. + double left_overhang{0.0}; ///< Left overhang of the vehicle. }; +/** + * @brief Represents a traffic signal with a timestamp. + */ struct TrafficSignalStamped { - builtin_interfaces::msg::Time stamp; - autoware_perception_msgs::msg::TrafficLightGroup signal; + builtin_interfaces::msg::Time stamp; ///< Timestamp of the signal. + autoware_perception_msgs::msg::TrafficLightGroup signal; ///< Traffic light group. }; using Pose = geometry_msgs::msg::Pose; @@ -70,21 +76,27 @@ namespace planning_utils size_t calcSegmentIndexFromPointIndex( const std::vector & points, const geometry_msgs::msg::Point & point, const size_t idx); -// create detection area from given range return false if creation failure + bool createDetectionAreaPolygons( Polygons2d & da_polys, const PathWithLaneId & path, const geometry_msgs::msg::Pose & target_pose, const size_t target_seg_idx, const DetectionRange & da_range, const double obstacle_vel_mps, const double min_velocity = 1.0); + Point2d calculateOffsetPoint2d( const geometry_msgs::msg::Pose & pose, const double offset_x, const double offset_y); + void extractClosePartition( const geometry_msgs::msg::Point position, const BasicPolygons2d & all_partitions, BasicPolygons2d & close_partition, const double distance_thresh = 30.0); -void getAllPartitionLanelets(const lanelet::LaneletMapConstPtr ll, BasicPolygons2d & polys); + +void getAllPartitionLanelets(const lanelet::LaneletMapConstPtr & ll, BasicPolygons2d & polys); + void setVelocityFromIndex(const size_t begin_idx, const double vel, PathWithLaneId * input); + void insertVelocity( PathWithLaneId & path, const PathPointWithLaneId & path_point, const double v, size_t & insert_index, const double min_distance = 0.001); + inline int64_t bitShift(int64_t original_id) { return original_id << (sizeof(int32_t) * 8 / 2); @@ -96,6 +108,7 @@ geometry_msgs::msg::Pose getAheadPose( const tier4_planning_msgs::msg::PathWithLaneId & path); Polygon2d generatePathPolygon( const PathWithLaneId & path, const size_t start_idx, const size_t end_idx, const double width); + double calcJudgeLineDistWithAccLimit( const double velocity, const double max_stop_acceleration, const double delay_response_time); @@ -210,6 +223,7 @@ bool isOverLine( std::optional insertStopPoint( const geometry_msgs::msg::Point & stop_point, PathWithLaneId & output); + std::optional insertStopPoint( const geometry_msgs::msg::Point & stop_point, const size_t stop_seg_idx, PathWithLaneId & output); @@ -218,11 +232,11 @@ std::optional insertStopPoint( or lane-changeable parent lanes with `lane` and has same turn_direction value. */ std::set getAssociativeIntersectionLanelets( - lanelet::ConstLanelet lane, const lanelet::LaneletMapPtr lanelet_map, + const lanelet::ConstLanelet & lane, const lanelet::LaneletMapPtr lanelet_map, const lanelet::routing::RoutingGraphPtr routing_graph); lanelet::ConstLanelets getConstLaneletsFromIds( - lanelet::LaneletMapConstPtr map, const std::set & ids); + const lanelet::LaneletMapConstPtr & map, const std::set & ids); } // namespace planning_utils } // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index 6692358f1b21f..105b0528940bf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -52,6 +52,7 @@ ament_cmake_ros ament_lint_auto autoware_lint_common + autoware_test_utils ament_cmake diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/planner_data.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/planner_data.cpp new file mode 100644 index 0000000000000..df2a183e3bfb3 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/planner_data.cpp @@ -0,0 +1,72 @@ +// Copyright 2019 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 "autoware/behavior_velocity_planner_common/planner_data.hpp" + +#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" + +#include + +namespace autoware::behavior_velocity_planner +{ +PlannerData::PlannerData(rclcpp::Node & node) +: clock_(node.get_clock()), + vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()) +{ + max_stop_acceleration_threshold = node.declare_parameter("max_accel"); + max_stop_jerk_threshold = node.declare_parameter("max_jerk"); + system_delay = node.declare_parameter("system_delay"); + delay_response_time = node.declare_parameter("delay_response_time"); +} + +bool PlannerData::isVehicleStopped(const double stop_duration) const +{ + if (velocity_buffer.empty()) { + return false; + } + + const auto now = clock_->now(); + std::vector vs; + for (const auto & velocity : velocity_buffer) { + vs.push_back(velocity.twist.linear.x); + + const auto & s = velocity.header.stamp; + const auto time_diff = + now >= s ? now - s : rclcpp::Duration(0, 0); // Note: negative time throws an exception. + if (time_diff.seconds() >= stop_duration) { + break; + } + } + + constexpr double stop_velocity = 1e-3; + for (const auto & v : vs) { + if (v >= stop_velocity) { + return false; + } + } + + return true; +} + +std::optional PlannerData::getTrafficSignal( + const lanelet::Id id, const bool keep_last_observation) const +{ + const auto & traffic_light_id_map = + keep_last_observation ? traffic_light_id_map_last_observed_ : traffic_light_id_map_raw_; + if (traffic_light_id_map.count(id) == 0) { + return std::nullopt; + } + return std::make_optional(traffic_light_id_map.at(id)); +} +} // namespace autoware::behavior_velocity_planner diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp index da6ef7262de74..9b02b374b0a6c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/arc_lane_util.cpp @@ -26,10 +26,7 @@ #include #endif -#include -#include #include -#include namespace { @@ -54,12 +51,6 @@ geometry_msgs::msg::Point operator*(const geometry_msgs::msg::Point & p, const d return multiplied_p; } -/* -geometry_msgs::msg::Point operator*(const double v, const geometry_msgs::msg::Point & p) -{ -return p * v; -} -*/ } // namespace namespace autoware::behavior_velocity_planner::arc_lane_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp index 33cf428e80808..d9162419ec33f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/boost_geometry_helper.cpp @@ -16,8 +16,6 @@ #include -#include -#include namespace autoware::behavior_velocity_planner { @@ -27,8 +25,8 @@ Polygon2d lines2polygon(const LineString2d & left_line, const LineString2d & rig polygon.outer().push_back(left_line.front()); - for (auto itr = right_line.begin(); itr != right_line.end(); ++itr) { - polygon.outer().push_back(*itr); + for (const auto & itr : right_line) { + polygon.outer().push_back(itr); } for (auto itr = left_line.rbegin(); itr != left_line.rend(); ++itr) { @@ -57,8 +55,8 @@ geometry_msgs::msg::Polygon toGeomPoly(const Polygon2d & polygon) geometry_msgs::msg::Polygon polygon_msg; geometry_msgs::msg::Point32 point_msg; for (const auto & p : polygon.outer()) { - point_msg.x = p.x(); - point_msg.y = p.y(); + point_msg.x = static_cast(p.x()); + point_msg.y = static_cast(p.y()); polygon_msg.points.push_back(point_msg); } return polygon_msg; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp index 7fe87bd285309..2ddf62bb584ff 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/debug.cpp @@ -18,14 +18,10 @@ #include #include -namespace autoware::behavior_velocity_planner +namespace autoware::behavior_velocity_planner::debug { -namespace debug -{ -using autoware::universe_utils::appendMarkerArray; using autoware::universe_utils::createDefaultMarker; using autoware::universe_utils::createMarkerColor; -using autoware::universe_utils::createMarkerOrientation; using autoware::universe_utils::createMarkerScale; visualization_msgs::msg::MarkerArray createPolygonMarkerArray( @@ -36,8 +32,9 @@ visualization_msgs::msg::MarkerArray createPolygonMarkerArray( visualization_msgs::msg::MarkerArray msg; { auto marker = createDefaultMarker( - "map", now, ns.c_str(), module_id, visualization_msgs::msg::Marker::LINE_STRIP, - createMarkerScale(x, y, z), createMarkerColor(r, g, b, 0.8)); + "map", now, ns, static_cast(module_id), visualization_msgs::msg::Marker::LINE_STRIP, + createMarkerScale(static_cast(x), static_cast(y), static_cast(z)), + createMarkerColor(static_cast(r), static_cast(g), static_cast(b), 0.8f)); marker.lifetime = rclcpp::Duration::from_seconds(0.3); for (const auto & p : polygon.points) { @@ -67,15 +64,18 @@ visualization_msgs::msg::MarkerArray createPathMarkerArray( const auto & p = path.points.at(i); auto marker = createDefaultMarker( - "map", now, ns.c_str(), planning_utils::bitShift(lane_id) + i, - visualization_msgs::msg::Marker::ARROW, createMarkerScale(x, y, z), - createMarkerColor(r, g, b, 0.999)); + "map", now, ns, static_cast(planning_utils::bitShift(lane_id) + i), + visualization_msgs::msg::Marker::ARROW, + createMarkerScale(static_cast(x), static_cast(y), static_cast(z)), + createMarkerColor( + static_cast(r), static_cast(g), static_cast(b), 0.999f)); marker.lifetime = rclcpp::Duration::from_seconds(0.3); marker.pose = p.point.pose; if (std::find(p.lane_ids.begin(), p.lane_ids.end(), lane_id) != p.lane_ids.end()) { // if p.lane_ids has lane_id - marker.color = createMarkerColor(r, g, b, 0.999); + marker.color = createMarkerColor( + static_cast(r), static_cast(g), static_cast(b), 0.999f); } else { marker.color = createMarkerColor(0.5, 0.5, 0.5, 0.999); } @@ -93,13 +93,13 @@ visualization_msgs::msg::MarkerArray createObjectsMarkerArray( auto marker = createDefaultMarker( "map", now, ns, 0, visualization_msgs::msg::Marker::CUBE, createMarkerScale(3.0, 1.0, 1.0), - createMarkerColor(r, g, b, 0.8)); + createMarkerColor(static_cast(r), static_cast(g), static_cast(b), 0.8f)); marker.lifetime = rclcpp::Duration::from_seconds(1.0); for (size_t i = 0; i < objects.objects.size(); ++i) { const auto & object = objects.objects.at(i); - marker.id = planning_utils::bitShift(module_id) + i; + marker.id = static_cast(planning_utils::bitShift(module_id) + i); marker.pose = object.kinematics.initial_pose_with_covariance.pose; msg.markers.push_back(marker); } @@ -116,15 +116,14 @@ visualization_msgs::msg::MarkerArray createPointsMarkerArray( auto marker = createDefaultMarker( "map", now, ns, 0, visualization_msgs::msg::Marker::SPHERE, createMarkerScale(x, y, z), - createMarkerColor(r, g, b, 0.999)); + createMarkerColor(static_cast(r), static_cast(g), static_cast(b), 0.999f)); marker.lifetime = rclcpp::Duration::from_seconds(0.3); for (size_t i = 0; i < points.size(); ++i) { - marker.id = i + planning_utils::bitShift(module_id); + marker.id = static_cast(i + planning_utils::bitShift(module_id)); marker.pose.position = points.at(i); msg.markers.push_back(marker); } return msg; } -} // namespace debug -} // namespace autoware::behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner::debug diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp index 17ea92022ea13..b8e6e28bae7c2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/path_utilization.cpp @@ -18,14 +18,13 @@ #include #include -#include #include namespace autoware::behavior_velocity_planner { bool splineInterpolate( const tier4_planning_msgs::msg::PathWithLaneId & input, const double interval, - tier4_planning_msgs::msg::PathWithLaneId & output, const rclcpp::Logger logger) + tier4_planning_msgs::msg::PathWithLaneId & output, const rclcpp::Logger & logger) { if (input.points.size() < 2) { RCLCPP_DEBUG(logger, "Do not interpolate because path size is 1."); @@ -156,12 +155,12 @@ autoware_planning_msgs::msg::Path filterStopPathPoint( { autoware_planning_msgs::msg::Path filtered_path = path; bool found_stop = false; - for (size_t i = 0; i < filtered_path.points.size(); ++i) { - if (std::fabs(filtered_path.points.at(i).longitudinal_velocity_mps) < 0.01) { + for (auto & point : filtered_path.points) { + if (std::fabs(point.longitudinal_velocity_mps) < 0.01) { found_stop = true; } if (found_stop) { - filtered_path.points.at(i).longitudinal_velocity_mps = 0.0; + point.longitudinal_velocity_mps = 0.0; } } return filtered_path; diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp index 72a6d29e7ba06..cb9b58ec48924 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/trajectory_utils.cpp @@ -79,13 +79,15 @@ bool smoothPath( TrajectoryPoints clipped; TrajectoryPoints traj_smoothed; clipped.insert( - clipped.end(), traj_resampled.begin() + traj_resampled_closest, traj_resampled.end()); + clipped.end(), traj_resampled.begin() + static_cast(traj_resampled_closest), + traj_resampled.end()); if (!smoother->apply(v0, a0, clipped, traj_smoothed, debug_trajectories, false)) { std::cerr << "[behavior_velocity][trajectory_utils]: failed to smooth" << std::endl; return false; } traj_smoothed.insert( - traj_smoothed.begin(), traj_resampled.begin(), traj_resampled.begin() + traj_resampled_closest); + traj_smoothed.begin(), traj_resampled.begin(), + traj_resampled.begin() + static_cast(traj_resampled_closest)); if (external_v_limit) { autoware::velocity_smoother::trajectory_utils::applyMaximumVelocityLimit( diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp index 1b1c47dc6fbb7..a8f909201ac7f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/src/utilization/util.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include -#include -#include +#include "autoware/behavior_velocity_planner_common/utilization/util.hpp" + +#include "autoware/behavior_velocity_planner_common/utilization/boost_geometry_helper.hpp" +#include "autoware/motion_utils/trajectory/trajectory.hpp" +#include "autoware_lanelet2_extension/utility/query.hpp" #include @@ -25,9 +26,6 @@ #include #include -#include -#include - #ifdef ROS_DISTRO_GALACTIC #include #else @@ -35,7 +33,9 @@ #endif #include -#include +#include +#include +#include #include #include @@ -67,7 +67,7 @@ PathPoint getLerpPathPointWithLaneId(const PathPoint p0, const PathPoint p1, con PathPoint p; p.pose = autoware::universe_utils::calcInterpolatedPose(p0, p1, ratio); const double v = lerp(p0.longitudinal_velocity_mps, p1.longitudinal_velocity_mps, ratio); - p.longitudinal_velocity_mps = v; + p.longitudinal_velocity_mps = static_cast(v); return p; } @@ -94,19 +94,11 @@ geometry_msgs::msg::Pose transformRelCoordinate2D( } // namespace -namespace autoware::behavior_velocity_planner -{ -namespace planning_utils +namespace autoware::behavior_velocity_planner::planning_utils { -using autoware::motion_utils::calcLongitudinalOffsetToSegment; using autoware::motion_utils::calcSignedArcLength; -using autoware::motion_utils::validateNonEmpty; -using autoware::universe_utils::calcAzimuthAngle; using autoware::universe_utils::calcDistance2d; using autoware::universe_utils::calcOffsetPose; -using autoware::universe_utils::calcSquaredDistance2d; -using autoware::universe_utils::createQuaternionFromYaw; -using autoware::universe_utils::getPoint; using autoware_planning_msgs::msg::PathPoint; size_t calcSegmentIndexFromPointIndex( @@ -157,7 +149,7 @@ bool createDetectionAreaPolygons( const double offset_right = (da_range.wheel_tread / 2.0) + da_range.right_overhang; //! max index is the last index of path point - const size_t max_index = static_cast(path.points.size() - 1); + const auto max_index = static_cast(path.points.size() - 1); //! avoid bug with same point polygon const double eps = 1e-3; auto nearest_idx = @@ -249,10 +241,9 @@ void extractClosePartition( close_partition.emplace_back(p); } } - return; } -void getAllPartitionLanelets(const lanelet::LaneletMapConstPtr ll, BasicPolygons2d & polys) +void getAllPartitionLanelets(const lanelet::LaneletMapConstPtr & ll, BasicPolygons2d & polys) { const lanelet::ConstLineStrings3d partitions = lanelet::utils::query::getAllPartitions(ll); for (const auto & partition : partitions) { @@ -262,7 +253,7 @@ void getAllPartitionLanelets(const lanelet::LaneletMapConstPtr ll, BasicPolygons } // correct line to calculate distance in accurate boost::geometry::correct(line); - polys.emplace_back(lanelet::BasicPolygon2d(line)); + polys.emplace_back(line); } } @@ -272,7 +263,6 @@ void setVelocityFromIndex(const size_t begin_idx, const double vel, PathWithLane input->points.at(i).point.longitudinal_velocity_mps = std::min(static_cast(vel), input->points.at(i).point.longitudinal_velocity_mps); } - return; } void insertVelocity( @@ -312,7 +302,7 @@ geometry_msgs::msg::Pose getAheadPose( const size_t start_idx, const double ahead_dist, const tier4_planning_msgs::msg::PathWithLaneId & path) { - if (path.points.size() == 0) { + if (path.points.empty()) { return geometry_msgs::msg::Pose{}; } @@ -330,7 +320,8 @@ geometry_msgs::msg::Pose getAheadPose( p.position.x = w_p0 * p0.position.x + w_p1 * p1.position.x; p.position.y = w_p0 * p0.position.y + w_p1 * p1.position.y; p.position.z = w_p0 * p0.position.z + w_p1 * p1.position.z; - tf2::Quaternion q0_tf, q1_tf; + tf2::Quaternion q0_tf; + tf2::Quaternion q1_tf; tf2::fromMsg(p0.orientation, q0_tf); tf2::fromMsg(p1.orientation, q1_tf); p.orientation = tf2::toMsg(q0_tf.slerp(q1_tf, w_p1)); @@ -427,15 +418,16 @@ double findReachTime( const int warn_iter = 100; double lower = min; double upper = max; - double t; + double t = NAN; int iter = 0; - for (int i = 0;; i++) { + while (true) { t = 0.5 * (lower + upper); const double fx = f(t, j, a, v, d); // std::cout<<"fx: "< 0.0) { + } + if (fx > 0.0) { upper = t; } else { lower = t; @@ -478,19 +470,18 @@ double calcDecelerationVelocityFromDistanceToTarget( const double t_jerk = findReachTime(j_max, a0, v0, l, 0, t_const_jerk); const double velocity = vt(t_jerk, j_max, a0, v0); return velocity; - } else { - const double v1 = vt(t_const_jerk, j_max, a0, v0); - const double discriminant_of_stop = 2.0 * a_max * d_const_acc_stop + v1 * v1; - // case3: distance to target is farther than distance to stop - if (discriminant_of_stop <= 0) { - return 0.0; - } - // case2: distance to target is within constant accel deceleration - // solve d = 0.5*a^2+v*t by t - const double t_acc = (-v1 + std::sqrt(discriminant_of_stop)) / a_max; - return vt(t_acc, 0.0, a_max, v1); } - return current_velocity; + + const double v1 = vt(t_const_jerk, j_max, a0, v0); + const double discriminant_of_stop = 2.0 * a_max * d_const_acc_stop + v1 * v1; + // case3: distance to target is farther than distance to stop + if (discriminant_of_stop <= 0) { + return 0.0; + } + // case2: distance to target is within constant accel deceleration + // solve d = 0.5*a^2+v*t by t + const double t_acc = (-v1 + std::sqrt(discriminant_of_stop)) / a_max; + return vt(t_acc, 0.0, a_max, v1); } std::vector toRosPoints(const PredictedObjects & object) @@ -549,6 +540,7 @@ std::vector getLaneletsOnPath( } std::vector lanelets; + lanelets.reserve(unique_lane_ids.size()); for (const auto lane_id : unique_lane_ids) { lanelets.push_back(lanelet_map->laneletLayer.get(lane_id)); } @@ -590,7 +582,7 @@ std::vector getSubsequentLaneIdsSetOnPath( // cannot find base_index in all_lane_ids if (base_index == all_lane_ids.end()) { - return std::vector(); + return {}; } std::vector subsequent_lane_ids; @@ -664,11 +656,11 @@ std::optional insertStopPoint( } std::set getAssociativeIntersectionLanelets( - lanelet::ConstLanelet lane, const lanelet::LaneletMapPtr lanelet_map, + const lanelet::ConstLanelet & lane, const lanelet::LaneletMapPtr lanelet_map, const lanelet::routing::RoutingGraphPtr routing_graph) { const std::string turn_direction = lane.attributeOr("turn_direction", "else"); - if (turn_direction.compare("else") == 0) { + if (turn_direction == "else") { return {}; } @@ -693,7 +685,7 @@ std::set getAssociativeIntersectionLanelets( } lanelet::ConstLanelets getConstLaneletsFromIds( - lanelet::LaneletMapConstPtr map, const std::set & ids) + const lanelet::LaneletMapConstPtr & map, const std::set & ids) { lanelet::ConstLanelets ret{}; for (const auto & id : ids) { @@ -703,5 +695,4 @@ lanelet::ConstLanelets getConstLaneletsFromIds( return ret; } -} // namespace planning_utils -} // namespace autoware::behavior_velocity_planner +} // namespace autoware::behavior_velocity_planner::planning_utils diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_path_utilization.cpp similarity index 70% rename from planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp rename to planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_path_utilization.cpp index d3664f2b46ffc..51c6b5b9dda04 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_utilization.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_path_utilization.cpp @@ -176,3 +176,70 @@ TEST(specialInterpolation, specialInterpolation) EXPECT_DOUBLE_EQ(calcInterpolatedStopDist(px, vx), expected); } } + +TEST(filterLitterPathPoint, nominal) +{ + using autoware::behavior_velocity_planner::filterLitterPathPoint; + using autoware_planning_msgs::msg::Path; + using autoware_planning_msgs::msg::PathPoint; + + const auto genPath = [](const std::vector & px, const std::vector & vx) { + Path path; + for (size_t i = 0; i < px.size(); ++i) { + PathPoint point; + point.pose.position.x = px[i]; + point.pose.position.y = 0.0; + point.longitudinal_velocity_mps = static_cast(vx[i]); + path.points.push_back(point); + } + return path; + }; + + const std::vector px{0.0, 1.0, 1.001, 2.0, 3.0}; + const std::vector vx{5.0, 3.5, 3.5, 3.0, 2.5}; + + const auto path = genPath(px, vx); + const auto filtered_path = filterLitterPathPoint(path); + + ASSERT_EQ(filtered_path.points.size(), 4U); // Expected: Points at x = {0.0, 1.0, 2.0, 3.0} + EXPECT_DOUBLE_EQ(filtered_path.points[0].pose.position.x, 0.0); + EXPECT_DOUBLE_EQ(filtered_path.points[1].pose.position.x, 1.0); + EXPECT_DOUBLE_EQ(filtered_path.points[2].pose.position.x, 2.0); + EXPECT_DOUBLE_EQ(filtered_path.points[3].pose.position.x, 3.0); + + EXPECT_DOUBLE_EQ(filtered_path.points[0].longitudinal_velocity_mps, 5.0); + EXPECT_DOUBLE_EQ(filtered_path.points[1].longitudinal_velocity_mps, 3.5); + EXPECT_DOUBLE_EQ(filtered_path.points[2].longitudinal_velocity_mps, 3.0); + EXPECT_DOUBLE_EQ(filtered_path.points[3].longitudinal_velocity_mps, 2.5); +} + +TEST(filterStopPathPoint, nominal) +{ + using autoware::behavior_velocity_planner::filterStopPathPoint; + using autoware_planning_msgs::msg::Path; + using autoware_planning_msgs::msg::PathPoint; + + const auto genPath = [](const std::vector & px, const std::vector & vx) { + Path path; + for (size_t i = 0; i < px.size(); ++i) { + PathPoint point; + point.pose.position.x = px[i]; + point.longitudinal_velocity_mps = static_cast(vx[i]); + path.points.push_back(point); + } + return path; + }; + + const std::vector px{0.0, 1.0, 2.0, 3.0, 4.0}; + const std::vector vx{5.0, 4.0, 0.0, 2.0, 3.0}; + + const auto path = genPath(px, vx); + const auto filtered_path = filterStopPathPoint(path); + + ASSERT_EQ(filtered_path.points.size(), 5U); + EXPECT_DOUBLE_EQ(filtered_path.points[0].longitudinal_velocity_mps, 5.0); + EXPECT_DOUBLE_EQ(filtered_path.points[1].longitudinal_velocity_mps, 4.0); + EXPECT_DOUBLE_EQ(filtered_path.points[2].longitudinal_velocity_mps, 0.0); + EXPECT_DOUBLE_EQ(filtered_path.points[3].longitudinal_velocity_mps, 0.0); + EXPECT_DOUBLE_EQ(filtered_path.points[4].longitudinal_velocity_mps, 0.0); +} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_trajectory_utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_trajectory_utils.cpp new file mode 100644 index 0000000000000..5ed490ab755a9 --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_trajectory_utils.cpp @@ -0,0 +1,113 @@ +// 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/behavior_velocity_planner_common/utilization/trajectory_utils.hpp" +#include "autoware/velocity_smoother/smoother/jerk_filtered_smoother.hpp" + +#include +#include + +#include +#include + +#include + +#include + +TEST(smoothPath, nominal) +{ + using autoware::behavior_velocity_planner::smoothPath; + using tier4_planning_msgs::msg::PathPointWithLaneId; + using tier4_planning_msgs::msg::PathWithLaneId; + + rclcpp::init(0, nullptr); + rclcpp::NodeOptions options; + options.arguments( + {"--ros-args", "--params-file", + ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_planner_common") + + "/config/behavior_velocity_planner_common.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_test_utils") + + "/config/test_vehicle_info.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_velocity_smoother") + + "/config/default_common.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_velocity_smoother") + + "/config/default_velocity_smoother.param.yaml", + "--params-file", + ament_index_cpp::get_package_share_directory("autoware_velocity_smoother") + + "/config/JerkFiltered.param.yaml"}); + auto node = std::make_shared("test_node", options); + + auto planner_data = std::make_shared(*node); + planner_data->stop_line_extend_length = 5.0; + planner_data->vehicle_info_.max_longitudinal_offset_m = 1.0; + + planner_data->current_odometry = std::make_shared([]() { + geometry_msgs::msg::PoseStamped pose; + pose.pose.position.x = 2.0; + pose.pose.position.y = 1.0; + return pose; + }()); + + planner_data->current_velocity = std::make_shared([]() { + geometry_msgs::msg::TwistStamped twist; + twist.twist.linear.x = 3.0; + return twist; + }()); + + planner_data->current_acceleration = + std::make_shared([]() { + geometry_msgs::msg::AccelWithCovarianceStamped accel; + accel.accel.accel.linear.x = 1.0; + return accel; + }()); + + planner_data->velocity_smoother_ = + std::make_shared( + *node, std::make_shared()); + + // Input path + PathWithLaneId in_path; + for (double i = 0; i <= 10.0; i += 1.0) { + PathPointWithLaneId point; + point.point.pose.position.x = i; + point.point.pose.position.y = 0.0; + point.point.longitudinal_velocity_mps = 5.0; // Set constant velocity + in_path.points.emplace_back(point); + } + + // Output path + PathWithLaneId out_path; + + // Execute smoothing + auto result = smoothPath(in_path, out_path, planner_data); + + // Check results + EXPECT_TRUE(result); + + // Check initial and last points + EXPECT_DOUBLE_EQ(out_path.points.front().point.pose.position.x, 0.0); + EXPECT_DOUBLE_EQ(out_path.points.front().point.pose.position.y, 0.0); + EXPECT_DOUBLE_EQ(out_path.points.back().point.pose.position.x, 10.0); + EXPECT_DOUBLE_EQ(out_path.points.back().point.pose.position.y, 0.0); + + for (auto & point : out_path.points) { + // Check velocities + EXPECT_LE( + point.point.longitudinal_velocity_mps, + 5.0); // Smoothed velocity must not exceed initial + } +} diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_util.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_util.cpp new file mode 100644 index 0000000000000..8c8ef575b5a9a --- /dev/null +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/test/src/test_util.cpp @@ -0,0 +1,308 @@ +// 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 "./utils.hpp" +#include "autoware/behavior_velocity_planner_common/utilization/util.hpp" +#include "autoware_test_utils/autoware_test_utils.hpp" + +#include +#include +#include +#include +#include + +#include + +using namespace autoware::behavior_velocity_planner; // NOLINT +using namespace autoware::behavior_velocity_planner::planning_utils; // NOLINT +using autoware_planning_msgs::msg::PathPoint; + +TEST(PlanningUtilsTest, calcSegmentIndexFromPointIndex) +{ + auto path = test::generatePath(0.0, 0.0, 10.0, 0.0, 10); + geometry_msgs::msg::Point point; + point.x = 4.5; + point.y = 0.0; + + size_t result = calcSegmentIndexFromPointIndex(path.points, point, 4); + + EXPECT_EQ(result, 4); +} + +TEST(PlanningUtilsTest, calculateOffsetPoint2d) +{ + geometry_msgs::msg::Pose pose; + pose.position.x = 0.0; + pose.position.y = 0.0; + pose.position.z = 0.0; + pose.orientation = tf2::toMsg(tf2::Quaternion(0, 0, 0, 1)); // No rotation + + double offset_x = 1.0; + double offset_y = 1.0; + + auto result = calculateOffsetPoint2d(pose, offset_x, offset_y); + + EXPECT_NEAR(result.x(), 1.0, 0.1); + EXPECT_NEAR(result.y(), 1.0, 0.1); +} + +TEST(PlanningUtilsTest, createDetectionAreaPolygons) +{ + // using namespace autoware::behavior_velocity_planner::planning_utils; + + // Input parameters + Polygons2d da_polys; + tier4_planning_msgs::msg::PathWithLaneId path; + geometry_msgs::msg::Pose target_pose; + size_t target_seg_idx = 0; + autoware::behavior_velocity_planner::DetectionRange da_range; + + da_range.min_longitudinal_distance = 1.0; + da_range.max_longitudinal_distance = 10.0; + da_range.max_lateral_distance = 2.0; + da_range.interval = 5.0; + da_range.wheel_tread = 1.0; + da_range.left_overhang = 0.5; + da_range.right_overhang = 0.5; + da_range.use_left = true; + da_range.use_right = true; + + double obstacle_vel_mps = 0.5; + double min_velocity = 1.0; + + // Path with some points + for (double i = 0.0; i < 3.0; ++i) { + tier4_planning_msgs::msg::PathPointWithLaneId point; + point.point.pose.position.x = i * 5.0; + point.point.pose.position.y = 0.0; + point.point.longitudinal_velocity_mps = 1.0; + path.points.push_back(point); + } + + // Target pose + target_pose.position.x = 0.0; + target_pose.position.y = 0.0; + + // Call the function + bool success = createDetectionAreaPolygons( + da_polys, path, target_pose, target_seg_idx, da_range, obstacle_vel_mps, min_velocity); + + // Assert success + EXPECT_TRUE(success); + + // Validate results + ASSERT_FALSE(da_polys.empty()); + EXPECT_EQ(da_polys.size(), 2); // Expect polygons for left and right bounds + + // Check the first polygon + auto & polygon = da_polys.front(); + EXPECT_EQ(polygon.outer().size(), 7); // Each polygon should be a rectangle + + // Check some specific points + EXPECT_NEAR(polygon.outer()[0].x(), 1.0, 0.1); // Left inner bound + EXPECT_NEAR(polygon.outer()[0].y(), 1.0, 0.1); +} + +// Test for calcJudgeLineDistWithAccLimit +TEST(PlanningUtilsTest, calcJudgeLineDistWithAccLimit) +{ + double velocity = 10.0; // m/s + double max_stop_acceleration = -3.0; // m/s^2 + double delay_response_time = 1.0; // s + + double result = + calcJudgeLineDistWithAccLimit(velocity, max_stop_acceleration, delay_response_time); + + EXPECT_NEAR(result, 26.67, 0.01); // Updated expected value +} + +// Test for calcJudgeLineDistWithJerkLimit +TEST(PlanningUtilsTest, calcJudgeLineDistWithJerkLimit) +{ + double velocity = 10.0; // m/s + double acceleration = 0.0; // m/s^2 + double max_stop_acceleration = -3.0; // m/s^2 + double max_stop_jerk = -1.0; // m/s^3 + double delay_response_time = 1.0; // s + + double result = calcJudgeLineDistWithJerkLimit( + velocity, acceleration, max_stop_acceleration, max_stop_jerk, delay_response_time); + + EXPECT_GT(result, 0.0); // The result should be positive +} + +// Test for isAheadOf +TEST(PlanningUtilsTest, isAheadOf) +{ + geometry_msgs::msg::Pose target; + geometry_msgs::msg::Pose origin; + target.position.x = 10.0; + target.position.y = 0.0; + origin.position.x = 0.0; + origin.position.y = 0.0; + origin.orientation = tf2::toMsg(tf2::Quaternion(0, 0, 0, 1)); // No rotation + + EXPECT_TRUE(isAheadOf(target, origin)); + + target.position.x = -10.0; + EXPECT_FALSE(isAheadOf(target, origin)); +} + +TEST(PlanningUtilsTest, insertDecelPoint) +{ + auto path = test::generatePath(0.0, 0.0, 10.0, 0.0, 10); + geometry_msgs::msg::Point stop_point; + stop_point.x = 5.0; + stop_point.y = 0.0; + + auto stop_pose = insertDecelPoint(stop_point, path, 5.0); + ASSERT_TRUE(stop_pose.has_value()); + EXPECT_NEAR(stop_pose->position.x, 5.0, 0.1); +} + +// Test for insertVelocity +TEST(PlanningUtilsTest, insertVelocity) +{ + auto path = test::generatePath(0.0, 0.0, 10.0, 0.0, 10); + tier4_planning_msgs::msg::PathPointWithLaneId path_point; + path_point.point.pose.position.x = 5.0; + path_point.point.pose.position.y = 0.0; + path_point.point.longitudinal_velocity_mps = 10.0; + + size_t insert_index = 5; + insertVelocity(path, path_point, 10.0, insert_index); + + EXPECT_EQ(path.points.size(), 11); + EXPECT_NEAR(path.points.at(insert_index).point.longitudinal_velocity_mps, 10.0, 0.1); +} + +// Test for insertStopPoint +TEST(PlanningUtilsTest, insertStopPoint) +{ + { + auto path = test::generatePath(0.0, 0.0, 10.0, 0.0, 10); + geometry_msgs::msg::Point stop_point; + stop_point.x = 5.0; + stop_point.y = 0.0; + + auto stop_pose = insertStopPoint(stop_point, path); + ASSERT_TRUE(stop_pose.has_value()); + EXPECT_NEAR(stop_pose->position.x, 5.0, 0.1); + } + { + auto path = test::generatePath(0.0, 0.0, 10.0, 0.0, 10); + geometry_msgs::msg::Point stop_point; + stop_point.x = 5.0; + stop_point.y = 0.0; + + auto stop_pose = insertStopPoint(stop_point, 4, path); + ASSERT_TRUE(stop_pose.has_value()); + EXPECT_NEAR(stop_pose->position.x, 5.0, 0.1); + } +} + +// Test for getAheadPose +TEST(PlanningUtilsTest, getAheadPose) +{ + tier4_planning_msgs::msg::PathWithLaneId path; + tier4_planning_msgs::msg::PathPointWithLaneId point1; + tier4_planning_msgs::msg::PathPointWithLaneId point2; + tier4_planning_msgs::msg::PathPointWithLaneId point3; + point1.point.pose.position.x = 0.0; + point2.point.pose.position.x = 5.0; + point3.point.pose.position.x = 10.0; + + path.points.emplace_back(point1); + path.points.emplace_back(point2); + path.points.emplace_back(point3); + + double ahead_dist = 7.0; + auto pose = getAheadPose(0, ahead_dist, path); + + EXPECT_NEAR(pose.position.x, 7.0, 0.1); +} + +TEST(PlanningUtilsTest, calcDecelerationVelocityFromDistanceToTarget) +{ + double max_slowdown_jerk = -1.0; // m/s^3 + double max_slowdown_accel = -3.0; // m/s^2 + double current_accel = -1.0; // m/s^2 + double current_velocity = 10.0; // m/s + double distance_to_target = 100.0; // m + + double result = calcDecelerationVelocityFromDistanceToTarget( + max_slowdown_jerk, max_slowdown_accel, current_accel, current_velocity, distance_to_target); + + EXPECT_LT(result, current_velocity); +} + +// Test for toRosPoints +TEST(PlanningUtilsTest, ToRosPoints) +{ + using autoware_perception_msgs::msg::PredictedObject; + PredictedObjects objects; + + // Add a predicted object + PredictedObject obj1; + obj1.kinematics.initial_pose_with_covariance.pose.position.x = 1.0; + obj1.kinematics.initial_pose_with_covariance.pose.position.y = 2.0; + obj1.kinematics.initial_pose_with_covariance.pose.position.z = 3.0; + objects.objects.push_back(obj1); + + // Add another predicted object + PredictedObject obj2; + obj2.kinematics.initial_pose_with_covariance.pose.position.x = 4.0; + obj2.kinematics.initial_pose_with_covariance.pose.position.y = 5.0; + obj2.kinematics.initial_pose_with_covariance.pose.position.z = 6.0; + objects.objects.push_back(obj2); + + auto points = toRosPoints(objects); + + ASSERT_EQ(points.size(), 2); // Verify the number of points + EXPECT_EQ(points[0].x, 1.0); + EXPECT_EQ(points[0].y, 2.0); + EXPECT_EQ(points[0].z, 3.0); + EXPECT_EQ(points[1].x, 4.0); + EXPECT_EQ(points[1].y, 5.0); + EXPECT_EQ(points[1].z, 6.0); +} + +// Test for extendLine +TEST(PlanningUtilsTest, ExtendLine) +{ + lanelet::ConstPoint3d point1(lanelet::InvalId, 0.0, 0.0, 0.0); + lanelet::ConstPoint3d point2(lanelet::InvalId, 1.0, 1.0, 0.0); + double length = 1.0; + + auto extended_line = extendLine(point1, point2, length); + + ASSERT_EQ(extended_line.size(), 2); // Verify the line has two points + + // Check the extended line coordinates + EXPECT_NEAR(extended_line[0].x(), -0.707, 0.001); // Extended in the reverse direction + EXPECT_NEAR(extended_line[0].y(), -0.707, 0.001); + EXPECT_NEAR(extended_line[1].x(), 1.707, 0.001); // Extended in the forward direction + EXPECT_NEAR(extended_line[1].y(), 1.707, 0.001); +} + +TEST(PlanningUtilsTest, getConstLaneletsFromIds) +{ + const auto package_dir = ament_index_cpp::get_package_share_directory("autoware_test_utils"); + lanelet::LaneletMapPtr map = + autoware::test_utils::loadMap(package_dir + "/test_map/lanelet2_map.osm"); + + auto lanelets = getConstLaneletsFromIds(map, {10333, 10310, 10291}); + + EXPECT_EQ(lanelets.size(), 3); +} From 3231bbfc703ed084509dd6349efb90a16bd299bc Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Fri, 6 Dec 2024 11:08:07 +0900 Subject: [PATCH 247/273] docs(autoware_pyplot): add missing readme and move the package to common (#9546) --- .../autoware_pyplot/CMakeLists.txt | 0 common/autoware_pyplot/README.md | 43 +++++++++++++++++++ .../include/autoware/pyplot/axes.hpp | 0 .../include/autoware/pyplot/common.hpp | 0 .../include/autoware/pyplot/figure.hpp | 0 .../include/autoware/pyplot/legend.hpp | 0 .../include/autoware/pyplot/loader.hpp | 0 .../include/autoware/pyplot/patches.hpp | 0 .../include/autoware/pyplot/pyplot.hpp | 0 .../include/autoware/pyplot/quiver.hpp | 0 .../include/autoware/pyplot/text.hpp | 0 .../autoware_pyplot/package.xml | 0 .../autoware_pyplot/src/axes.cpp | 0 .../autoware_pyplot/src/common.cpp | 0 .../autoware_pyplot/src/figure.cpp | 0 .../autoware_pyplot/src/legend.cpp | 0 .../autoware_pyplot/src/patches.cpp | 0 .../autoware_pyplot/src/pyplot.cpp | 0 .../autoware_pyplot/src/quiver.cpp | 0 .../autoware_pyplot/src/text.cpp | 0 .../autoware_pyplot/test/test_pyplot.cpp | 0 21 files changed, 43 insertions(+) rename {visualization => common}/autoware_pyplot/CMakeLists.txt (100%) create mode 100644 common/autoware_pyplot/README.md rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/axes.hpp (100%) rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/common.hpp (100%) rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/figure.hpp (100%) rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/legend.hpp (100%) rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/loader.hpp (100%) rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/patches.hpp (100%) rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/pyplot.hpp (100%) rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/quiver.hpp (100%) rename {visualization => common}/autoware_pyplot/include/autoware/pyplot/text.hpp (100%) rename {visualization => common}/autoware_pyplot/package.xml (100%) rename {visualization => common}/autoware_pyplot/src/axes.cpp (100%) rename {visualization => common}/autoware_pyplot/src/common.cpp (100%) rename {visualization => common}/autoware_pyplot/src/figure.cpp (100%) rename {visualization => common}/autoware_pyplot/src/legend.cpp (100%) rename {visualization => common}/autoware_pyplot/src/patches.cpp (100%) rename {visualization => common}/autoware_pyplot/src/pyplot.cpp (100%) rename {visualization => common}/autoware_pyplot/src/quiver.cpp (100%) rename {visualization => common}/autoware_pyplot/src/text.cpp (100%) rename {visualization => common}/autoware_pyplot/test/test_pyplot.cpp (100%) diff --git a/visualization/autoware_pyplot/CMakeLists.txt b/common/autoware_pyplot/CMakeLists.txt similarity index 100% rename from visualization/autoware_pyplot/CMakeLists.txt rename to common/autoware_pyplot/CMakeLists.txt diff --git a/common/autoware_pyplot/README.md b/common/autoware_pyplot/README.md new file mode 100644 index 0000000000000..ded3387fefd99 --- /dev/null +++ b/common/autoware_pyplot/README.md @@ -0,0 +1,43 @@ +# autoware_pyplot + +This package provides C++ interface for the notable `matplotlib` using `pybind11` backend for + +- creating scientific plots and images illustrating the function inputs/outputs +- debugging the output and internal data of a function before unit testing in a more lightweight manner than planning_simulator + +## usage + +In your main function, setup the python context and import `matplotlib` + +```cpp +#include +#include + +// in main... + py::scoped_interpreter guard{}; + auto plt = autoware::pyplot::import(); +``` + +Then you can use major functionalities of `matplotlib` almost in the same way as native python code. + +```cpp +{ + plt.plot(Args(std::vector({1, 3, 2, 4})), Kwargs("color"_a = "blue", "linewidth"_a = 1.0)); + plt.xlabel(Args("x-title")); + plt.ylabel(Args("y-title")); + plt.title(Args("title")); + plt.xlim(Args(0, 5)); + plt.ylim(Args(0, 5)); + plt.grid(Args(true)); + plt.savefig(Args("test_single_plot.png")); +} + +{ + auto [fig, axes] = plt.subplots(1, 2); + auto & ax1 = axes[0]; + auto & ax2 = axes[1]; + + ax1.set_aspect(Args("equal")); + ax2.set_aspect(Args("equal")); +} +``` diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/axes.hpp b/common/autoware_pyplot/include/autoware/pyplot/axes.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/axes.hpp rename to common/autoware_pyplot/include/autoware/pyplot/axes.hpp diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/common.hpp b/common/autoware_pyplot/include/autoware/pyplot/common.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/common.hpp rename to common/autoware_pyplot/include/autoware/pyplot/common.hpp diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/figure.hpp b/common/autoware_pyplot/include/autoware/pyplot/figure.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/figure.hpp rename to common/autoware_pyplot/include/autoware/pyplot/figure.hpp diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/legend.hpp b/common/autoware_pyplot/include/autoware/pyplot/legend.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/legend.hpp rename to common/autoware_pyplot/include/autoware/pyplot/legend.hpp diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/loader.hpp b/common/autoware_pyplot/include/autoware/pyplot/loader.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/loader.hpp rename to common/autoware_pyplot/include/autoware/pyplot/loader.hpp diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/patches.hpp b/common/autoware_pyplot/include/autoware/pyplot/patches.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/patches.hpp rename to common/autoware_pyplot/include/autoware/pyplot/patches.hpp diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/pyplot.hpp b/common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/pyplot.hpp rename to common/autoware_pyplot/include/autoware/pyplot/pyplot.hpp diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/quiver.hpp b/common/autoware_pyplot/include/autoware/pyplot/quiver.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/quiver.hpp rename to common/autoware_pyplot/include/autoware/pyplot/quiver.hpp diff --git a/visualization/autoware_pyplot/include/autoware/pyplot/text.hpp b/common/autoware_pyplot/include/autoware/pyplot/text.hpp similarity index 100% rename from visualization/autoware_pyplot/include/autoware/pyplot/text.hpp rename to common/autoware_pyplot/include/autoware/pyplot/text.hpp diff --git a/visualization/autoware_pyplot/package.xml b/common/autoware_pyplot/package.xml similarity index 100% rename from visualization/autoware_pyplot/package.xml rename to common/autoware_pyplot/package.xml diff --git a/visualization/autoware_pyplot/src/axes.cpp b/common/autoware_pyplot/src/axes.cpp similarity index 100% rename from visualization/autoware_pyplot/src/axes.cpp rename to common/autoware_pyplot/src/axes.cpp diff --git a/visualization/autoware_pyplot/src/common.cpp b/common/autoware_pyplot/src/common.cpp similarity index 100% rename from visualization/autoware_pyplot/src/common.cpp rename to common/autoware_pyplot/src/common.cpp diff --git a/visualization/autoware_pyplot/src/figure.cpp b/common/autoware_pyplot/src/figure.cpp similarity index 100% rename from visualization/autoware_pyplot/src/figure.cpp rename to common/autoware_pyplot/src/figure.cpp diff --git a/visualization/autoware_pyplot/src/legend.cpp b/common/autoware_pyplot/src/legend.cpp similarity index 100% rename from visualization/autoware_pyplot/src/legend.cpp rename to common/autoware_pyplot/src/legend.cpp diff --git a/visualization/autoware_pyplot/src/patches.cpp b/common/autoware_pyplot/src/patches.cpp similarity index 100% rename from visualization/autoware_pyplot/src/patches.cpp rename to common/autoware_pyplot/src/patches.cpp diff --git a/visualization/autoware_pyplot/src/pyplot.cpp b/common/autoware_pyplot/src/pyplot.cpp similarity index 100% rename from visualization/autoware_pyplot/src/pyplot.cpp rename to common/autoware_pyplot/src/pyplot.cpp diff --git a/visualization/autoware_pyplot/src/quiver.cpp b/common/autoware_pyplot/src/quiver.cpp similarity index 100% rename from visualization/autoware_pyplot/src/quiver.cpp rename to common/autoware_pyplot/src/quiver.cpp diff --git a/visualization/autoware_pyplot/src/text.cpp b/common/autoware_pyplot/src/text.cpp similarity index 100% rename from visualization/autoware_pyplot/src/text.cpp rename to common/autoware_pyplot/src/text.cpp diff --git a/visualization/autoware_pyplot/test/test_pyplot.cpp b/common/autoware_pyplot/test/test_pyplot.cpp similarity index 100% rename from visualization/autoware_pyplot/test/test_pyplot.cpp rename to common/autoware_pyplot/test/test_pyplot.cpp From 0bbdbe14abc12a03c46af69abe27e38cc0c5fbd0 Mon Sep 17 00:00:00 2001 From: Masaki Baba Date: Fri, 6 Dec 2024 13:41:30 +0900 Subject: [PATCH 248/273] refactor(vehicle_velocity_converter)!: prefix package and namespace with autoware (#8967) * add autoware prefix Signed-off-by: a-maumau * fix conflict Signed-off-by: a-maumau --------- Signed-off-by: a-maumau Co-authored-by: Yamato Ando --- .github/_CODEOWNERS | 2 +- .../tier4_simulator_launch/launch/simulator.launch.xml | 4 ++-- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 4 ++-- .../README.md | 2 +- .../config/vehicle_velocity_converter.param.yaml | 0 .../launch/vehicle_velocity_converter.launch.xml | 4 ++-- .../package.xml | 4 ++-- .../schema/vehicle_velocity_converter.json | 0 .../src/vehicle_velocity_converter.cpp | 7 +++++-- .../src}/vehicle_velocity_converter.hpp | 9 ++++++--- 11 files changed, 21 insertions(+), 15 deletions(-) rename sensing/{vehicle_velocity_converter => autoware_vehicle_velocity_converter}/CHANGELOG.rst (100%) rename sensing/{vehicle_velocity_converter => autoware_vehicle_velocity_converter}/CMakeLists.txt (75%) rename sensing/{vehicle_velocity_converter => autoware_vehicle_velocity_converter}/README.md (97%) rename sensing/{vehicle_velocity_converter => autoware_vehicle_velocity_converter}/config/vehicle_velocity_converter.param.yaml (100%) rename sensing/{vehicle_velocity_converter => autoware_vehicle_velocity_converter}/launch/vehicle_velocity_converter.launch.xml (60%) rename sensing/{vehicle_velocity_converter => autoware_vehicle_velocity_converter}/package.xml (84%) rename sensing/{vehicle_velocity_converter => autoware_vehicle_velocity_converter}/schema/vehicle_velocity_converter.json (100%) rename sensing/{vehicle_velocity_converter => autoware_vehicle_velocity_converter}/src/vehicle_velocity_converter.cpp (91%) rename sensing/{vehicle_velocity_converter/include/vehicle_velocity_converter => autoware_vehicle_velocity_converter/src}/vehicle_velocity_converter.hpp (86%) diff --git a/.github/_CODEOWNERS b/.github/_CODEOWNERS index 4923e144f2886..3c1defb31a741 100644 --- a/.github/_CODEOWNERS +++ b/.github/_CODEOWNERS @@ -211,7 +211,7 @@ sensing/autoware_radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shuns sensing/autoware_radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/autoware_radar_tracks_noise_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp -sensing/vehicle_velocity_converter/** ryu.yamamoto@tier4.jp +sensing/autoware_vehicle_velocity_converter/** ryu.yamamoto@tier4.jp simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail.com simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp simulator/fault_injection/** keisuke.shima@tier4.jp diff --git a/launch/tier4_simulator_launch/launch/simulator.launch.xml b/launch/tier4_simulator_launch/launch/simulator.launch.xml index e1226ee63f5e2..4b2cefa02c2fa 100644 --- a/launch/tier4_simulator_launch/launch/simulator.launch.xml +++ b/launch/tier4_simulator_launch/launch/simulator.launch.xml @@ -188,9 +188,9 @@ - + - + diff --git a/sensing/vehicle_velocity_converter/CHANGELOG.rst b/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst similarity index 100% rename from sensing/vehicle_velocity_converter/CHANGELOG.rst rename to sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst diff --git a/sensing/vehicle_velocity_converter/CMakeLists.txt b/sensing/autoware_vehicle_velocity_converter/CMakeLists.txt similarity index 75% rename from sensing/vehicle_velocity_converter/CMakeLists.txt rename to sensing/autoware_vehicle_velocity_converter/CMakeLists.txt index bb50fbff90c4b..9ff990b928f91 100644 --- a/sensing/vehicle_velocity_converter/CMakeLists.txt +++ b/sensing/autoware_vehicle_velocity_converter/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.14) -project(vehicle_velocity_converter) +project(autoware_vehicle_velocity_converter) 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 "VehicleVelocityConverter" + PLUGIN "autoware::vehicle_velocity_converter::VehicleVelocityConverter" EXECUTABLE ${PROJECT_NAME}_node EXECUTOR SingleThreadedExecutor ) diff --git a/sensing/vehicle_velocity_converter/README.md b/sensing/autoware_vehicle_velocity_converter/README.md similarity index 97% rename from sensing/vehicle_velocity_converter/README.md rename to sensing/autoware_vehicle_velocity_converter/README.md index 3c7292f3fcdc4..f398a72ea824d 100644 --- a/sensing/vehicle_velocity_converter/README.md +++ b/sensing/autoware_vehicle_velocity_converter/README.md @@ -1,4 +1,4 @@ -# vehicle_velocity_converter +# autoware_vehicle_velocity_converter ## Purpose diff --git a/sensing/vehicle_velocity_converter/config/vehicle_velocity_converter.param.yaml b/sensing/autoware_vehicle_velocity_converter/config/vehicle_velocity_converter.param.yaml similarity index 100% rename from sensing/vehicle_velocity_converter/config/vehicle_velocity_converter.param.yaml rename to sensing/autoware_vehicle_velocity_converter/config/vehicle_velocity_converter.param.yaml diff --git a/sensing/vehicle_velocity_converter/launch/vehicle_velocity_converter.launch.xml b/sensing/autoware_vehicle_velocity_converter/launch/vehicle_velocity_converter.launch.xml similarity index 60% rename from sensing/vehicle_velocity_converter/launch/vehicle_velocity_converter.launch.xml rename to sensing/autoware_vehicle_velocity_converter/launch/vehicle_velocity_converter.launch.xml index 84e1838dc89eb..d8386e3b80820 100644 --- a/sensing/vehicle_velocity_converter/launch/vehicle_velocity_converter.launch.xml +++ b/sensing/autoware_vehicle_velocity_converter/launch/vehicle_velocity_converter.launch.xml @@ -1,9 +1,9 @@ - + - + diff --git a/sensing/vehicle_velocity_converter/package.xml b/sensing/autoware_vehicle_velocity_converter/package.xml similarity index 84% rename from sensing/vehicle_velocity_converter/package.xml rename to sensing/autoware_vehicle_velocity_converter/package.xml index 57400454b9d8e..323002396c841 100644 --- a/sensing/vehicle_velocity_converter/package.xml +++ b/sensing/autoware_vehicle_velocity_converter/package.xml @@ -1,9 +1,9 @@ - vehicle_velocity_converter + autoware_vehicle_velocity_converter 0.38.0 - The vehicle_velocity_converter package + The autoware_vehicle_velocity_converter package Ryu Yamamoto Apache License 2.0 diff --git a/sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json b/sensing/autoware_vehicle_velocity_converter/schema/vehicle_velocity_converter.json similarity index 100% rename from sensing/vehicle_velocity_converter/schema/vehicle_velocity_converter.json rename to sensing/autoware_vehicle_velocity_converter/schema/vehicle_velocity_converter.json diff --git a/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp b/sensing/autoware_vehicle_velocity_converter/src/vehicle_velocity_converter.cpp similarity index 91% rename from sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp rename to sensing/autoware_vehicle_velocity_converter/src/vehicle_velocity_converter.cpp index ab9787fb6020d..2211fa0cbb03e 100644 --- a/sensing/vehicle_velocity_converter/src/vehicle_velocity_converter.cpp +++ b/sensing/autoware_vehicle_velocity_converter/src/vehicle_velocity_converter.cpp @@ -12,10 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "vehicle_velocity_converter/vehicle_velocity_converter.hpp" +#include "vehicle_velocity_converter.hpp" #include +namespace autoware::vehicle_velocity_converter +{ VehicleVelocityConverter::VehicleVelocityConverter(const rclcpp::NodeOptions & options) : rclcpp::Node("vehicle_velocity_converter", options) { @@ -55,6 +57,7 @@ void VehicleVelocityConverter::callback_velocity_report( twist_with_covariance_pub_->publish(twist_with_covariance_msg); } +} // namespace autoware::vehicle_velocity_converter #include -RCLCPP_COMPONENTS_REGISTER_NODE(VehicleVelocityConverter) +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::vehicle_velocity_converter::VehicleVelocityConverter) diff --git a/sensing/vehicle_velocity_converter/include/vehicle_velocity_converter/vehicle_velocity_converter.hpp b/sensing/autoware_vehicle_velocity_converter/src/vehicle_velocity_converter.hpp similarity index 86% rename from sensing/vehicle_velocity_converter/include/vehicle_velocity_converter/vehicle_velocity_converter.hpp rename to sensing/autoware_vehicle_velocity_converter/src/vehicle_velocity_converter.hpp index 5f7b1c044d7e3..9d65e34c4457c 100644 --- a/sensing/vehicle_velocity_converter/include/vehicle_velocity_converter/vehicle_velocity_converter.hpp +++ b/sensing/autoware_vehicle_velocity_converter/src/vehicle_velocity_converter.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_ -#define VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_ +#ifndef VEHICLE_VELOCITY_CONVERTER_HPP_ +#define VEHICLE_VELOCITY_CONVERTER_HPP_ #include @@ -25,6 +25,8 @@ #include #include +namespace autoware::vehicle_velocity_converter +{ class VehicleVelocityConverter : public rclcpp::Node { public: @@ -43,5 +45,6 @@ class VehicleVelocityConverter : public rclcpp::Node double stddev_wz_; double speed_scale_factor_; }; +} // namespace autoware::vehicle_velocity_converter -#endif // VEHICLE_VELOCITY_CONVERTER__VEHICLE_VELOCITY_CONVERTER_HPP_ +#endif // VEHICLE_VELOCITY_CONVERTER_HPP_ From ede3f237c0b4c3632ba2a24aaddb4f2a4deb5573 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Fri, 6 Dec 2024 16:14:09 +0900 Subject: [PATCH 249/273] feat(goal_planner): check opposite lane for lane departure_check (#9460) * feat(goal_planner): check opposite lane for lane departure_check Signed-off-by: kosuke55 * refactor getMostInnerLane Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../src/util.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp index 8ca9d9ab45dc3..a2a64fc700676 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp @@ -723,8 +723,13 @@ lanelet::Lanelet createDepartureCheckLanelet( }; const auto getMostInnerLane = [&](const lanelet::ConstLanelet & lane) -> lanelet::ConstLanelet { - return left_side_parking ? route_handler.getMostRightLanelet(lane, false, true) - : route_handler.getMostLeftLanelet(lane, false, true); + const auto getInnerLane = + left_side_parking ? &RouteHandler::getMostRightLanelet : &RouteHandler::getMostLeftLanelet; + const auto getOppositeLane = left_side_parking ? &RouteHandler::getRightOppositeLanelets + : &RouteHandler::getLeftOppositeLanelets; + const auto inner_lane = (route_handler.*getInnerLane)(lane, true, true); + const auto opposite_lanes = (route_handler.*getOppositeLane)(inner_lane); + return opposite_lanes.empty() ? inner_lane : opposite_lanes.front(); }; lanelet::Points3d outer_bound_points{}; From 9c7ec8abcdcde77aed447fc4c292ee8dfc8875c5 Mon Sep 17 00:00:00 2001 From: SakodaShintaro Date: Fri, 6 Dec 2024 19:25:41 +0900 Subject: [PATCH 250/273] fix: autoware_glog_compontnt (#9586) Fixed autoware_glog_compontnt Signed-off-by: Shintaro Sakoda --- launch/tier4_control_launch/launch/control.launch.xml | 4 ++-- .../behavior_planning/behavior_planning.launch.xml | 2 +- .../lane_driving/motion_planning/motion_planning.launch.xml | 2 +- .../launch/scenario_planning/parking.launch.xml | 2 +- .../launch/scenario_planning/scenario_planning.launch.xml | 2 +- .../launch/mission_planner.launch.xml | 2 +- 6 files changed, 7 insertions(+), 7 deletions(-) diff --git a/launch/tier4_control_launch/launch/control.launch.xml b/launch/tier4_control_launch/launch/control.launch.xml index a979f9e28244b..2b0339f1c5cad 100644 --- a/launch/tier4_control_launch/launch/control.launch.xml +++ b/launch/tier4_control_launch/launch/control.launch.xml @@ -51,7 +51,7 @@ - + @@ -177,7 +177,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 41326c1a16728..3579884064d5d 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -255,7 +255,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml index fb7e11419fdc9..555e8da787013 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/motion_planning/motion_planning.launch.xml @@ -27,7 +27,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml index 89961821fa761..1daeebe87d4eb 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/parking.launch.xml @@ -32,7 +32,7 @@ - + diff --git a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml index a89b47da13049..d90515f6cb335 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/scenario_planning.launch.xml @@ -44,7 +44,7 @@ - + diff --git a/planning/autoware_mission_planner/launch/mission_planner.launch.xml b/planning/autoware_mission_planner/launch/mission_planner.launch.xml index 0d9c9307d549c..c15874118011a 100644 --- a/planning/autoware_mission_planner/launch/mission_planner.launch.xml +++ b/planning/autoware_mission_planner/launch/mission_planner.launch.xml @@ -23,6 +23,6 @@ - + From c9f0f2688c57b0f657f5c1f28f036a970682e7f5 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Date: Fri, 6 Dec 2024 23:34:04 +0900 Subject: [PATCH 251/273] chore(package.xml): bump version to 0.39.0 (#9587) * chore(package.xml): bump version to 0.39.0 Signed-off-by: Yutaka Kondo * fix: fix ticket links in CHANGELOG.rst Signed-off-by: Ryohsuke Mitsudome * fix: remove unnecessary diff Signed-off-by: Ryohsuke Mitsudome --------- Signed-off-by: Yutaka Kondo Signed-off-by: Ryohsuke Mitsudome Co-authored-by: Yutaka Kondo --- common/autoware_adapi_specs/CHANGELOG.rst | 16 ++++++ common/autoware_adapi_specs/package.xml | 2 +- common/autoware_auto_common/CHANGELOG.rst | 14 ++++++ common/autoware_auto_common/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 13 +++++ .../package.xml | 2 +- common/autoware_fake_test_node/CHANGELOG.rst | 12 +++++ common/autoware_fake_test_node/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- common/autoware_glog_component/CHANGELOG.rst | 12 +++++ common/autoware_glog_component/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- common/autoware_grid_map_utils/CHANGELOG.rst | 12 +++++ common/autoware_grid_map_utils/package.xml | 2 +- common/autoware_interpolation/CHANGELOG.rst | 12 +++++ common/autoware_interpolation/package.xml | 2 +- common/autoware_kalman_filter/CHANGELOG.rst | 12 +++++ common/autoware_kalman_filter/package.xml | 2 +- common/autoware_motion_utils/CHANGELOG.rst | 50 +++++++++++++++++++ common/autoware_motion_utils/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- common/autoware_osqp_interface/CHANGELOG.rst | 12 +++++ common/autoware_osqp_interface/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../autoware_overlay_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- common/autoware_point_types/CHANGELOG.rst | 12 +++++ common/autoware_point_types/package.xml | 2 +- common/autoware_polar_grid/CHANGELOG.rst | 12 +++++ common/autoware_polar_grid/package.xml | 2 +- common/autoware_pyplot/package.xml | 3 +- common/autoware_qp_interface/CHANGELOG.rst | 13 +++++ common/autoware_qp_interface/package.xml | 2 +- .../autoware_signal_processing/CHANGELOG.rst | 12 +++++ common/autoware_signal_processing/package.xml | 2 +- common/autoware_test_utils/CHANGELOG.rst | 32 ++++++++++++ common/autoware_test_utils/package.xml | 2 +- common/autoware_testing/CHANGELOG.rst | 12 +++++ common/autoware_testing/package.xml | 2 +- common/autoware_time_utils/CHANGELOG.rst | 18 +++++++ common/autoware_time_utils/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../autoware_traffic_light_utils/package.xml | 2 +- common/autoware_trajectory/CHANGELOG.rst | 46 +++++++++++++++++ common/autoware_trajectory/package.xml | 2 +- common/autoware_universe_utils/CHANGELOG.rst | 16 ++++++ common/autoware_universe_utils/package.xml | 2 +- .../autoware_vehicle_info_utils/CHANGELOG.rst | 12 +++++ .../autoware_vehicle_info_utils/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../bag_time_manager_rviz_plugin/package.xml | 2 +- common/tier4_adapi_rviz_plugin/CHANGELOG.rst | 24 +++++++++ common/tier4_adapi_rviz_plugin/package.xml | 2 +- common/tier4_api_utils/CHANGELOG.rst | 12 +++++ common/tier4_api_utils/package.xml | 2 +- .../CHANGELOG.rst | 24 +++++++++ .../tier4_camera_view_rviz_plugin/package.xml | 2 +- .../tier4_datetime_rviz_plugin/CHANGELOG.rst | 12 +++++ common/tier4_datetime_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../tier4_planning_rviz_plugin/CHANGELOG.rst | 12 +++++ common/tier4_planning_rviz_plugin/package.xml | 2 +- common/tier4_state_rviz_plugin/CHANGELOG.rst | 14 ++++++ common/tier4_state_rviz_plugin/package.xml | 2 +- common/tier4_system_rviz_plugin/CHANGELOG.rst | 12 +++++ common/tier4_system_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../tier4_vehicle_rviz_plugin/CHANGELOG.rst | 14 ++++++ common/tier4_vehicle_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 41 +++++++++++++++ .../package.xml | 2 +- .../autoware_collision_detector/CHANGELOG.rst | 20 ++++++++ .../autoware_collision_detector/package.xml | 2 +- .../autoware_control_validator/CHANGELOG.rst | 14 ++++++ .../autoware_control_validator/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- control/autoware_joy_controller/CHANGELOG.rst | 12 +++++ control/autoware_joy_controller/package.xml | 2 +- .../CHANGELOG.rst | 15 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 18 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- control/autoware_pure_pursuit/CHANGELOG.rst | 14 ++++++ control/autoware_pure_pursuit/package.xml | 2 +- control/autoware_shift_decider/CHANGELOG.rst | 12 +++++ control/autoware_shift_decider/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../autoware_vehicle_cmd_gate/CHANGELOG.rst | 16 ++++++ control/autoware_vehicle_cmd_gate/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../control_performance_analysis/package.xml | 2 +- control/predicted_path_checker/CHANGELOG.rst | 14 ++++++ control/predicted_path_checker/package.xml | 2 +- .../autoware_control_evaluator/CHANGELOG.rst | 40 +++++++++++++++ .../autoware_control_evaluator/package.xml | 2 +- .../autoware_planning_evaluator/CHANGELOG.rst | 36 +++++++++++++ .../autoware_planning_evaluator/package.xml | 2 +- evaluator/kinematic_evaluator/CHANGELOG.rst | 12 +++++ evaluator/kinematic_evaluator/package.xml | 2 +- .../localization_evaluator/CHANGELOG.rst | 12 +++++ evaluator/localization_evaluator/package.xml | 2 +- .../perception_online_evaluator/CHANGELOG.rst | 12 +++++ .../perception_online_evaluator/package.xml | 2 +- .../scenario_simulator_v2_adapter/package.xml | 2 +- .../tier4_autoware_api_launch/CHANGELOG.rst | 12 +++++ launch/tier4_autoware_api_launch/package.xml | 2 +- launch/tier4_control_launch/CHANGELOG.rst | 27 ++++++++++ launch/tier4_control_launch/package.xml | 2 +- .../tier4_localization_launch/CHANGELOG.rst | 12 +++++ launch/tier4_localization_launch/package.xml | 2 +- launch/tier4_map_launch/CHANGELOG.rst | 12 +++++ launch/tier4_map_launch/package.xml | 2 +- launch/tier4_perception_launch/CHANGELOG.rst | 12 +++++ launch/tier4_perception_launch/package.xml | 2 +- launch/tier4_planning_launch/CHANGELOG.rst | 12 +++++ launch/tier4_planning_launch/package.xml | 2 +- launch/tier4_sensing_launch/CHANGELOG.rst | 12 +++++ launch/tier4_sensing_launch/package.xml | 2 +- launch/tier4_simulator_launch/CHANGELOG.rst | 36 +++++++++++++ launch/tier4_simulator_launch/package.xml | 2 +- launch/tier4_system_launch/CHANGELOG.rst | 12 +++++ launch/tier4_system_launch/package.xml | 2 +- launch/tier4_vehicle_launch/CHANGELOG.rst | 12 +++++ launch/tier4_vehicle_launch/package.xml | 2 +- .../autoware_ekf_localizer/CHANGELOG.rst | 15 ++++++ .../autoware_ekf_localizer/package.xml | 2 +- .../autoware_geo_pose_projector/CHANGELOG.rst | 14 ++++++ .../autoware_geo_pose_projector/package.xml | 2 +- .../autoware_gyro_odometer/CHANGELOG.rst | 12 +++++ .../autoware_gyro_odometer/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_landmark_manager/CHANGELOG.rst | 12 +++++ .../autoware_landmark_manager/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_localization_util/CHANGELOG.rst | 12 +++++ .../autoware_localization_util/package.xml | 2 +- .../autoware_ndt_scan_matcher/CHANGELOG.rst | 50 +++++++++++++++++++ .../autoware_ndt_scan_matcher/package.xml | 2 +- .../autoware_pose2twist/CHANGELOG.rst | 12 +++++ localization/autoware_pose2twist/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_pose_initializer/CHANGELOG.rst | 14 ++++++ .../autoware_pose_initializer/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_stop_filter/CHANGELOG.rst | 12 +++++ localization/autoware_stop_filter/package.xml | 2 +- .../autoware_twist2accel/CHANGELOG.rst | 12 +++++ localization/autoware_twist2accel/package.xml | 2 +- .../yabloc/yabloc_common/CHANGELOG.rst | 12 +++++ localization/yabloc/yabloc_common/package.xml | 2 +- .../yabloc_image_processing/CHANGELOG.rst | 12 +++++ .../yabloc_image_processing/package.xml | 2 +- .../yabloc/yabloc_monitor/CHANGELOG.rst | 12 +++++ .../yabloc/yabloc_monitor/package.xml | 2 +- .../yabloc_particle_filter/CHANGELOG.rst | 12 +++++ .../yabloc/yabloc_particle_filter/package.xml | 2 +- .../yabloc_pose_initializer/CHANGELOG.rst | 12 +++++ .../yabloc_pose_initializer/package.xml | 2 +- map/autoware_map_height_fitter/CHANGELOG.rst | 12 +++++ map/autoware_map_height_fitter/package.xml | 2 +- map/autoware_map_loader/CHANGELOG.rst | 14 ++++++ map/autoware_map_loader/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- map/autoware_map_tf_generator/CHANGELOG.rst | 12 +++++ map/autoware_map_tf_generator/package.xml | 2 +- perception/autoware_bytetrack/CHANGELOG.rst | 14 ++++++ perception/autoware_bytetrack/package.xml | 2 +- .../autoware_cluster_merger/CHANGELOG.rst | 12 +++++ .../autoware_cluster_merger/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../autoware_detection_by_tracker/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../autoware_elevation_map_loader/package.xml | 2 +- .../autoware_euclidean_cluster/CHANGELOG.rst | 15 ++++++ .../autoware_euclidean_cluster/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../autoware_ground_segmentation/package.xml | 2 +- .../CHANGELOG.rst | 23 +++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 15 ++++++ .../package.xml | 2 +- .../autoware_lidar_centerpoint/CHANGELOG.rst | 12 +++++ .../autoware_lidar_centerpoint/package.xml | 2 +- .../autoware_lidar_transfusion/CHANGELOG.rst | 12 +++++ .../autoware_lidar_transfusion/package.xml | 2 +- .../CHANGELOG.rst | 30 +++++++++++ .../autoware_map_based_prediction/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../autoware_multi_object_tracker/package.xml | 2 +- .../autoware_object_merger/CHANGELOG.rst | 12 +++++ perception/autoware_object_merger/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 15 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../autoware_radar_object_tracker/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_shape_estimation/CHANGELOG.rst | 14 ++++++ .../autoware_shape_estimation/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../autoware_simple_object_merger/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../autoware_tensorrt_classifier/package.xml | 2 +- .../autoware_tensorrt_common/CHANGELOG.rst | 12 +++++ .../autoware_tensorrt_common/package.xml | 2 +- .../autoware_tensorrt_yolox/CHANGELOG.rst | 14 ++++++ .../autoware_tensorrt_yolox/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 18 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- perception/perception_utils/CHANGELOG.rst | 12 +++++ perception/perception_utils/package.xml | 2 +- .../autoware_costmap_generator/CHANGELOG.rst | 29 +++++++++++ .../autoware_costmap_generator/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_freespace_planner/CHANGELOG.rst | 12 +++++ .../autoware_freespace_planner/package.xml | 2 +- .../CHANGELOG.rst | 16 ++++++ .../package.xml | 2 +- .../autoware_mission_planner/CHANGELOG.rst | 12 +++++ planning/autoware_mission_planner/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 39 +++++++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_path_optimizer/CHANGELOG.rst | 12 +++++ planning/autoware_path_optimizer/package.xml | 2 +- planning/autoware_path_smoother/CHANGELOG.rst | 12 +++++ planning/autoware_path_smoother/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_planning_validator/CHANGELOG.rst | 12 +++++ .../autoware_planning_validator/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- planning/autoware_route_handler/CHANGELOG.rst | 12 +++++ planning/autoware_route_handler/package.xml | 2 +- planning/autoware_rtc_interface/CHANGELOG.rst | 24 +++++++++ planning/autoware_rtc_interface/package.xml | 2 +- .../autoware_scenario_selector/CHANGELOG.rst | 12 +++++ .../autoware_scenario_selector/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_velocity_smoother/CHANGELOG.rst | 14 ++++++ .../autoware_velocity_smoother/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 39 +++++++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 35 +++++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 16 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 25 ++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 15 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 19 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 17 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 19 +++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 36 +++++++++++++ .../package.xml | 2 +- .../autoware_bezier_sampler/CHANGELOG.rst | 12 +++++ .../autoware_bezier_sampler/package.xml | 2 +- .../autoware_frenet_planner/CHANGELOG.rst | 12 +++++ .../autoware_frenet_planner/package.xml | 2 +- .../autoware_path_sampler/CHANGELOG.rst | 12 +++++ .../autoware_path_sampler/package.xml | 2 +- .../autoware_sampler_common/CHANGELOG.rst | 12 +++++ .../autoware_sampler_common/package.xml | 2 +- sensing/autoware_cuda_utils/CHANGELOG.rst | 17 ++++++- sensing/autoware_cuda_utils/package.xml | 2 +- sensing/autoware_gnss_poser/CHANGELOG.rst | 14 ++++++ sensing/autoware_gnss_poser/package.xml | 2 +- .../autoware_image_diagnostics/CHANGELOG.rst | 12 +++++ .../autoware_image_diagnostics/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- sensing/autoware_imu_corrector/CHANGELOG.rst | 12 +++++ sensing/autoware_imu_corrector/package.xml | 2 +- sensing/autoware_pcl_extensions/CHANGELOG.rst | 12 +++++ sensing/autoware_pcl_extensions/package.xml | 2 +- .../CHANGELOG.rst | 21 ++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../autoware_livox_tag_filter/CHANGELOG.rst | 12 +++++ .../autoware_livox_tag_filter/package.xml | 2 +- .../autoware_carla_interface/CHANGELOG.rst | 12 +++++ .../autoware_carla_interface/package.xml | 2 +- .../dummy_perception_publisher/CHANGELOG.rst | 12 +++++ .../dummy_perception_publisher/package.xml | 2 +- simulator/fault_injection/CHANGELOG.rst | 12 +++++ simulator/fault_injection/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../learning_based_vehicle_model/package.xml | 2 +- .../simple_planning_simulator/CHANGELOG.rst | 12 +++++ .../simple_planning_simulator/package.xml | 2 +- .../CHANGELOG.rst | 14 ++++++ .../package.xml | 2 +- .../vehicle_door_simulator/CHANGELOG.rst | 12 +++++ simulator/vehicle_door_simulator/package.xml | 2 +- .../autoware_component_monitor/CHANGELOG.rst | 12 +++++ system/autoware_component_monitor/package.xml | 2 +- system/autoware_default_adapi/CHANGELOG.rst | 26 ++++++++++ system/autoware_default_adapi/package.xml | 2 +- .../CHANGELOG.rst | 36 +++++++++++++ .../package.xml | 2 +- system/bluetooth_monitor/CHANGELOG.rst | 12 +++++ system/bluetooth_monitor/package.xml | 2 +- system/component_state_monitor/CHANGELOG.rst | 12 +++++ system/component_state_monitor/package.xml | 2 +- .../ad_api_adaptors/CHANGELOG.rst | 24 +++++++++ .../ad_api_adaptors/package.xml | 2 +- .../ad_api_visualizers/CHANGELOG.rst | 12 +++++ .../ad_api_visualizers/package.xml | 2 +- .../ad_api_visualizers/setup.py | 2 +- .../automatic_pose_initializer/CHANGELOG.rst | 24 +++++++++ .../automatic_pose_initializer/package.xml | 2 +- .../diagnostic_graph_aggregator/CHANGELOG.rst | 14 ++++++ .../diagnostic_graph_aggregator/package.xml | 2 +- system/diagnostic_graph_utils/CHANGELOG.rst | 15 ++++++ system/diagnostic_graph_utils/package.xml | 2 +- system/dummy_diag_publisher/CHANGELOG.rst | 22 ++++++++ system/dummy_diag_publisher/package.xml | 2 +- system/dummy_infrastructure/CHANGELOG.rst | 12 +++++ system/dummy_infrastructure/package.xml | 2 +- system/duplicated_node_checker/CHANGELOG.rst | 12 +++++ system/duplicated_node_checker/package.xml | 2 +- system/hazard_status_converter/CHANGELOG.rst | 12 +++++ system/hazard_status_converter/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../mrm_comfortable_stop_operator/package.xml | 2 +- .../mrm_emergency_stop_operator/CHANGELOG.rst | 12 +++++ .../mrm_emergency_stop_operator/package.xml | 2 +- system/mrm_handler/CHANGELOG.rst | 12 +++++ system/mrm_handler/package.xml | 2 +- .../system_diagnostic_monitor/CHANGELOG.rst | 12 +++++ system/system_diagnostic_monitor/package.xml | 2 +- system/system_monitor/CHANGELOG.rst | 22 ++++++++ system/system_monitor/package.xml | 2 +- system/topic_state_monitor/CHANGELOG.rst | 12 +++++ system/topic_state_monitor/package.xml | 2 +- system/velodyne_monitor/CHANGELOG.rst | 12 +++++ system/velodyne_monitor/package.xml | 2 +- tools/reaction_analyzer/CHANGELOG.rst | 12 +++++ tools/reaction_analyzer/package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 12 +++++ .../package.xml | 2 +- 489 files changed, 3890 insertions(+), 248 deletions(-) create mode 100644 common/autoware_trajectory/CHANGELOG.rst diff --git a/common/autoware_adapi_specs/CHANGELOG.rst b/common/autoware_adapi_specs/CHANGELOG.rst index b4fec15bfa98c..79e62f7738922 100644 --- a/common/autoware_adapi_specs/CHANGELOG.rst +++ b/common/autoware_adapi_specs/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package autoware_adapi_specs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_adapi_specs/package.xml b/common/autoware_adapi_specs/package.xml index a949084dd8789..754edf9ddfbe7 100644 --- a/common/autoware_adapi_specs/package.xml +++ b/common/autoware_adapi_specs/package.xml @@ -2,7 +2,7 @@ autoware_adapi_specs - 0.38.0 + 0.39.0 The autoware_adapi_specs package Takagi, Isamu Ryohsuke Mitsudome diff --git a/common/autoware_auto_common/CHANGELOG.rst b/common/autoware_auto_common/CHANGELOG.rst index 271ecb7badb38..93b2dba7939a2 100644 --- a/common/autoware_auto_common/CHANGELOG.rst +++ b/common/autoware_auto_common/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_auto_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_auto_common/package.xml b/common/autoware_auto_common/package.xml index 1a462ee9db7ac..9d12bda8c75c3 100644 --- a/common/autoware_auto_common/package.xml +++ b/common/autoware_auto_common/package.xml @@ -2,7 +2,7 @@ autoware_auto_common - 0.38.0 + 0.39.0 Miscellaneous helper functions Apex.AI, Inc. Tomoya Kimura diff --git a/common/autoware_component_interface_specs/CHANGELOG.rst b/common/autoware_component_interface_specs/CHANGELOG.rst index 68a4eaaa2f36b..faacc0cfdb2bf 100644 --- a/common/autoware_component_interface_specs/CHANGELOG.rst +++ b/common/autoware_component_interface_specs/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_component_interface_specs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_component_interface_specs/package.xml b/common/autoware_component_interface_specs/package.xml index 0fbd632d52af3..5a2fd993613d1 100644 --- a/common/autoware_component_interface_specs/package.xml +++ b/common/autoware_component_interface_specs/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_specs - 0.38.0 + 0.39.0 The autoware_component_interface_specs package Takagi, Isamu Yukihiro Saito diff --git a/common/autoware_component_interface_tools/CHANGELOG.rst b/common/autoware_component_interface_tools/CHANGELOG.rst index d04567161c80d..e0c07efa43418 100644 --- a/common/autoware_component_interface_tools/CHANGELOG.rst +++ b/common/autoware_component_interface_tools/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_component_interface_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_component_interface_tools/package.xml b/common/autoware_component_interface_tools/package.xml index 96514517e1574..d0c79f3ad0d67 100644 --- a/common/autoware_component_interface_tools/package.xml +++ b/common/autoware_component_interface_tools/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_tools - 0.38.0 + 0.39.0 The autoware_component_interface_tools package Takagi, Isamu Apache License 2.0 diff --git a/common/autoware_component_interface_utils/CHANGELOG.rst b/common/autoware_component_interface_utils/CHANGELOG.rst index d7f476f33409a..6e6ee88a3f3a7 100644 --- a/common/autoware_component_interface_utils/CHANGELOG.rst +++ b/common/autoware_component_interface_utils/CHANGELOG.rst @@ -2,6 +2,19 @@ Changelog for package autoware_component_interface_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_component_interface_utils/package.xml b/common/autoware_component_interface_utils/package.xml index f1902d159e818..5efebf5c0d210 100755 --- a/common/autoware_component_interface_utils/package.xml +++ b/common/autoware_component_interface_utils/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_utils - 0.38.0 + 0.39.0 The autoware_component_interface_utils package Takagi, Isamu Yukihiro Saito diff --git a/common/autoware_fake_test_node/CHANGELOG.rst b/common/autoware_fake_test_node/CHANGELOG.rst index 330dddaa66aef..5f04908a8ab0f 100644 --- a/common/autoware_fake_test_node/CHANGELOG.rst +++ b/common/autoware_fake_test_node/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_fake_test_node ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_fake_test_node/package.xml b/common/autoware_fake_test_node/package.xml index 413f359eafbcc..531e9351023e6 100644 --- a/common/autoware_fake_test_node/package.xml +++ b/common/autoware_fake_test_node/package.xml @@ -2,7 +2,7 @@ autoware_fake_test_node - 0.38.0 + 0.39.0 A fake node that we can use in the integration-like cpp tests. Apex.AI, Inc. Tomoya Kimura diff --git a/common/autoware_global_parameter_loader/CHANGELOG.rst b/common/autoware_global_parameter_loader/CHANGELOG.rst index ae5dfd0509592..2de0adf89cb3e 100644 --- a/common/autoware_global_parameter_loader/CHANGELOG.rst +++ b/common/autoware_global_parameter_loader/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package global_parameter_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_global_parameter_loader/package.xml b/common/autoware_global_parameter_loader/package.xml index 2a72f93230da9..ef40ff8df22aa 100644 --- a/common/autoware_global_parameter_loader/package.xml +++ b/common/autoware_global_parameter_loader/package.xml @@ -2,7 +2,7 @@ autoware_global_parameter_loader - 0.38.0 + 0.39.0 The autoware_global_parameter_loader package Ryohsuke Mitsudome Apache License 2.0 diff --git a/common/autoware_glog_component/CHANGELOG.rst b/common/autoware_glog_component/CHANGELOG.rst index b305cfb616e27..66eee038b6353 100644 --- a/common/autoware_glog_component/CHANGELOG.rst +++ b/common/autoware_glog_component/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package glog_component ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_glog_component/package.xml b/common/autoware_glog_component/package.xml index f9e6a1aa26723..3bfb6c97155b0 100644 --- a/common/autoware_glog_component/package.xml +++ b/common/autoware_glog_component/package.xml @@ -2,7 +2,7 @@ autoware_glog_component - 0.38.0 + 0.39.0 The autoware_glog_component package Takamasa Horibe Apache License 2.0 diff --git a/common/autoware_goal_distance_calculator/CHANGELOG.rst b/common/autoware_goal_distance_calculator/CHANGELOG.rst index 4b38ad848193b..45fa8825612ef 100644 --- a/common/autoware_goal_distance_calculator/CHANGELOG.rst +++ b/common/autoware_goal_distance_calculator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_goal_distance_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_goal_distance_calculator/package.xml b/common/autoware_goal_distance_calculator/package.xml index 4ad84b9f4f283..24b3b2f2ba9c6 100644 --- a/common/autoware_goal_distance_calculator/package.xml +++ b/common/autoware_goal_distance_calculator/package.xml @@ -2,7 +2,7 @@ autoware_goal_distance_calculator - 0.38.0 + 0.39.0 The autoware_goal_distance_calculator package Taiki Tanaka Apache License 2.0 diff --git a/common/autoware_grid_map_utils/CHANGELOG.rst b/common/autoware_grid_map_utils/CHANGELOG.rst index ee66753285b0e..31df087b80d59 100644 --- a/common/autoware_grid_map_utils/CHANGELOG.rst +++ b/common/autoware_grid_map_utils/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_grid_map_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_grid_map_utils/package.xml b/common/autoware_grid_map_utils/package.xml index 40c1ba7c96e87..cc64daa0045e0 100644 --- a/common/autoware_grid_map_utils/package.xml +++ b/common/autoware_grid_map_utils/package.xml @@ -2,7 +2,7 @@ autoware_grid_map_utils - 0.38.0 + 0.39.0 Utilities for the grid_map library Maxime CLEMENT Apache License 2.0 diff --git a/common/autoware_interpolation/CHANGELOG.rst b/common/autoware_interpolation/CHANGELOG.rst index fbba411fcdeca..e62e73ae4ec21 100644 --- a/common/autoware_interpolation/CHANGELOG.rst +++ b/common/autoware_interpolation/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_interpolation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_interpolation/package.xml b/common/autoware_interpolation/package.xml index e94ec898cb0cb..22db75271b316 100644 --- a/common/autoware_interpolation/package.xml +++ b/common/autoware_interpolation/package.xml @@ -2,7 +2,7 @@ autoware_interpolation - 0.38.0 + 0.39.0 The spline interpolation package Fumiya Watanabe Takayuki Murooka diff --git a/common/autoware_kalman_filter/CHANGELOG.rst b/common/autoware_kalman_filter/CHANGELOG.rst index becf8dc95abec..5ec0bcc9e72dc 100644 --- a/common/autoware_kalman_filter/CHANGELOG.rst +++ b/common/autoware_kalman_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_kalman_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_kalman_filter/package.xml b/common/autoware_kalman_filter/package.xml index a3c454795344b..4cd94ff488899 100644 --- a/common/autoware_kalman_filter/package.xml +++ b/common/autoware_kalman_filter/package.xml @@ -2,7 +2,7 @@ autoware_kalman_filter - 0.38.0 + 0.39.0 The kalman filter package Yukihiro Saito Takeshi Ishita diff --git a/common/autoware_motion_utils/CHANGELOG.rst b/common/autoware_motion_utils/CHANGELOG.rst index 84374fb8a3f26..216d4d978bd8a 100644 --- a/common/autoware_motion_utils/CHANGELOG.rst +++ b/common/autoware_motion_utils/CHANGELOG.rst @@ -2,6 +2,56 @@ Changelog for package autoware_motion_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(autoware_trajectory): move trajectory_container from autoware_motion_utils to a new package (`#9253 `_) + * create trajectory container package + * update + * update + * style(pre-commit): autofix + * update codeowner + * update + * fix cmake + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_motion_utils): add new trajectory class (`#8693 `_) + * feat(autoware_motion_utils): add interpolator + * use int32_t instead of int + * use int32_t instead of int + * use int32_t instead of int + * add const as much as possible and use `at()` in `vector` + * fix directory name + * refactor code and add example + * update + * remove unused include + * refactor code + * add clone function + * fix stairstep + * make constructor to public + * feat(autoware_motion_utils): add trajectory class + * Update CMakeLists.txt + * fix + * fix package.xml + * update crop + * revert crtp change + * update package.xml + * updating... + * update + * solve build problem + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Yukinari Hisaki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_motion_utils/package.xml b/common/autoware_motion_utils/package.xml index 6fbe84927a9e3..4aa215b48e2ce 100644 --- a/common/autoware_motion_utils/package.xml +++ b/common/autoware_motion_utils/package.xml @@ -2,7 +2,7 @@ autoware_motion_utils - 0.38.0 + 0.39.0 The autoware_motion_utils package Satoshi Ota Takayuki Murooka diff --git a/common/autoware_object_recognition_utils/CHANGELOG.rst b/common/autoware_object_recognition_utils/CHANGELOG.rst index 1ff6a870e3791..44bc2573f435a 100644 --- a/common/autoware_object_recognition_utils/CHANGELOG.rst +++ b/common/autoware_object_recognition_utils/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_object_recognition_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_object_recognition_utils/package.xml b/common/autoware_object_recognition_utils/package.xml index 353a6af544783..729999f96dc6e 100644 --- a/common/autoware_object_recognition_utils/package.xml +++ b/common/autoware_object_recognition_utils/package.xml @@ -2,7 +2,7 @@ autoware_object_recognition_utils - 0.38.0 + 0.39.0 The autoware_object_recognition_utils package Takayuki Murooka Shunsuke Miura diff --git a/common/autoware_osqp_interface/CHANGELOG.rst b/common/autoware_osqp_interface/CHANGELOG.rst index 5af614d9301ad..5ce7b02250fda 100644 --- a/common/autoware_osqp_interface/CHANGELOG.rst +++ b/common/autoware_osqp_interface/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_osqp_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_osqp_interface/package.xml b/common/autoware_osqp_interface/package.xml index 063617716bdd6..95ffebe833cc6 100644 --- a/common/autoware_osqp_interface/package.xml +++ b/common/autoware_osqp_interface/package.xml @@ -2,7 +2,7 @@ autoware_osqp_interface - 0.38.0 + 0.39.0 Interface for the OSQP solver Maxime CLEMENT Takayuki Murooka diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst index 86a9f62f236fa..7fdc075553c07 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_mission_details_overlay_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index 1865376069def..1ae744322766e 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_mission_details_overlay_rviz_plugin - 0.38.0 + 0.39.0 RViz2 plugin for 2D overlays for mission details in the 3D view. Mainly a port of the JSK overlay plugin (https://github.com/jsk-ros-pkg/jsk_visualization). diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst index 012be9e7cce85..b1cef0c598a85 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_overlay_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix: missing dependency in common components (`#9072 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo, ぐるぐる + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml index 6b0ee4fbd355e..1a626d90bc02b 100644 --- a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml +++ b/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_overlay_rviz_plugin - 0.38.0 + 0.39.0 RViz2 plugin for 2D overlays in the 3D view. Mainly a port of the JSK overlay plugin (https://github.com/jsk-ros-pkg/jsk_visualization). diff --git a/common/autoware_path_distance_calculator/CHANGELOG.rst b/common/autoware_path_distance_calculator/CHANGELOG.rst index 436099b87795e..6adf0a3e3c851 100644 --- a/common/autoware_path_distance_calculator/CHANGELOG.rst +++ b/common/autoware_path_distance_calculator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_path_distance_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_path_distance_calculator/package.xml b/common/autoware_path_distance_calculator/package.xml index e9042c4385b66..7466b299e7e2e 100644 --- a/common/autoware_path_distance_calculator/package.xml +++ b/common/autoware_path_distance_calculator/package.xml @@ -2,7 +2,7 @@ autoware_path_distance_calculator - 0.38.0 + 0.39.0 The autoware_path_distance_calculator package Takagi, Isamu Apache License 2.0 diff --git a/common/autoware_perception_rviz_plugin/CHANGELOG.rst b/common/autoware_perception_rviz_plugin/CHANGELOG.rst index 0f8e5ff1f7fd8..c84cd5bf35fa8 100644 --- a/common/autoware_perception_rviz_plugin/CHANGELOG.rst +++ b/common/autoware_perception_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_perception_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_perception_rviz_plugin/package.xml b/common/autoware_perception_rviz_plugin/package.xml index 98c24297894b6..3f6c168c9857a 100644 --- a/common/autoware_perception_rviz_plugin/package.xml +++ b/common/autoware_perception_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_perception_rviz_plugin - 0.38.0 + 0.39.0 Contains plugins to visualize object detection outputs Apex.AI, Inc. Taiki Tanaka diff --git a/common/autoware_point_types/CHANGELOG.rst b/common/autoware_point_types/CHANGELOG.rst index 3aa6d4183543e..12cef4043ae3e 100644 --- a/common/autoware_point_types/CHANGELOG.rst +++ b/common/autoware_point_types/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_point_types ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_point_types/package.xml b/common/autoware_point_types/package.xml index 8e9fb4fb51aa4..fd48c12daa2e9 100644 --- a/common/autoware_point_types/package.xml +++ b/common/autoware_point_types/package.xml @@ -2,7 +2,7 @@ autoware_point_types - 0.38.0 + 0.39.0 The point types definition to use point_cloud_msg_wrapper David Wong Max Schmeller diff --git a/common/autoware_polar_grid/CHANGELOG.rst b/common/autoware_polar_grid/CHANGELOG.rst index 359de11cb3104..b4e9e612fe093 100644 --- a/common/autoware_polar_grid/CHANGELOG.rst +++ b/common/autoware_polar_grid/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_polar_grid ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_polar_grid/package.xml b/common/autoware_polar_grid/package.xml index f14776b145349..a2ed7a138bdca 100644 --- a/common/autoware_polar_grid/package.xml +++ b/common/autoware_polar_grid/package.xml @@ -2,7 +2,7 @@ autoware_polar_grid - 0.38.0 + 0.39.0 The autoware_polar_grid package Yukihiro Saito Apache License 2.0 diff --git a/common/autoware_pyplot/package.xml b/common/autoware_pyplot/package.xml index af0237d0aead8..297ab68cb9367 100644 --- a/common/autoware_pyplot/package.xml +++ b/common/autoware_pyplot/package.xml @@ -2,11 +2,12 @@ autoware_pyplot - 0.1.0 + 0.39.0 C++ interface for matplotlib based on pybind11 Mamoru Sobue Yukinari Hisaki Apache License 2.0 + Koji Minoda Mamoru Sobue diff --git a/common/autoware_qp_interface/CHANGELOG.rst b/common/autoware_qp_interface/CHANGELOG.rst index 17e296bab4fca..ce931f6f5e1e7 100644 --- a/common/autoware_qp_interface/CHANGELOG.rst +++ b/common/autoware_qp_interface/CHANGELOG.rst @@ -2,6 +2,19 @@ Changelog for package autoware_qp_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_qp_interface/package.xml b/common/autoware_qp_interface/package.xml index 43c9c6607bcaa..5bd3ce1ad8464 100644 --- a/common/autoware_qp_interface/package.xml +++ b/common/autoware_qp_interface/package.xml @@ -2,7 +2,7 @@ autoware_qp_interface - 0.38.0 + 0.39.0 Interface for the QP solvers Takayuki Murooka Fumiya Watanabe diff --git a/common/autoware_signal_processing/CHANGELOG.rst b/common/autoware_signal_processing/CHANGELOG.rst index f0293aefdc69d..f41732a258cf7 100644 --- a/common/autoware_signal_processing/CHANGELOG.rst +++ b/common/autoware_signal_processing/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_signal_processing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_signal_processing/package.xml b/common/autoware_signal_processing/package.xml index 952833d10c59a..6197c641a6f82 100644 --- a/common/autoware_signal_processing/package.xml +++ b/common/autoware_signal_processing/package.xml @@ -2,7 +2,7 @@ autoware_signal_processing - 0.38.0 + 0.39.0 The signal processing package Takayuki Murooka Takamasa Horibe diff --git a/common/autoware_test_utils/CHANGELOG.rst b/common/autoware_test_utils/CHANGELOG.rst index b9600e7cb7f22..02a046a20e595 100644 --- a/common/autoware_test_utils/CHANGELOG.rst +++ b/common/autoware_test_utils/CHANGELOG.rst @@ -2,6 +2,38 @@ Changelog for package autoware_test_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* test(costmap_generator): unit test implementation for costmap generator (`#9149 `_) + * modify costmap generator directory structure + * rename class CostmapGenerator to CostmapGeneratorNode + * unit test for object_map_utils + * catch error from lookupTransform + * use polling subscriber in costmap generator node + * add test for costmap generator node + * add test for isActive() + * revert unnecessary changes + * remove commented out line + * minor fix + * Update planning/autoware_costmap_generator/src/costmap_generator.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(autoware_test_utils): use sample_vehicle/sample_sensor_kit (`#9290 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(autoware_test_utils): add general topic dumper (`#9207 `_) +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* feat(autoware_test_utils): add traffic light msgs parser (`#9177 `_) +* Contributors: Esteve Fernandez, Mamoru Sobue, Yutaka Kondo, mkquda + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index 712a3569a658b..97c81c62ba512 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -2,7 +2,7 @@ autoware_test_utils - 0.38.0 + 0.39.0 ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara Takamasa Horibe diff --git a/common/autoware_testing/CHANGELOG.rst b/common/autoware_testing/CHANGELOG.rst index 36ad1ec42c3c5..1a016888fda47 100644 --- a/common/autoware_testing/CHANGELOG.rst +++ b/common/autoware_testing/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_testing/package.xml b/common/autoware_testing/package.xml index 483b8323e224f..ae5b5e7a5d466 100644 --- a/common/autoware_testing/package.xml +++ b/common/autoware_testing/package.xml @@ -2,7 +2,7 @@ autoware_testing - 0.38.0 + 0.39.0 Tools for handling standard tests based on ros_testing Adam Dabrowski Tomoya Kimura diff --git a/common/autoware_time_utils/CHANGELOG.rst b/common/autoware_time_utils/CHANGELOG.rst index 43074de077e04..4f0f87e5daad8 100644 --- a/common/autoware_time_utils/CHANGELOG.rst +++ b/common/autoware_time_utils/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package autoware_time_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(time_utils): prefix package and namespace with autoware (`#9173 `_) + * refactor(time_utils): prefix package and namespace with autoware + * refactor(time_utils): prefix package and namespace with autoware + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_time_utils/package.xml b/common/autoware_time_utils/package.xml index 988ebad188839..6491006b6cc27 100644 --- a/common/autoware_time_utils/package.xml +++ b/common/autoware_time_utils/package.xml @@ -2,7 +2,7 @@ autoware_time_utils - 0.38.0 + 0.39.0 Simple conversion methods to/from std::chrono to simplify algorithm development Christopher Ho Tomoya Kimura diff --git a/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst index 98691121f4d30..ea5339ba8d566 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst +++ b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_traffic_light_recognition_marker_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_traffic_light_recognition_marker_publisher/package.xml b/common/autoware_traffic_light_recognition_marker_publisher/package.xml index 88addcfb77b44..ddca8ad56c281 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/package.xml +++ b/common/autoware_traffic_light_recognition_marker_publisher/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_recognition_marker_publisher - 0.38.0 + 0.39.0 The autoware_traffic_light_recognition_marker_publisher package Tomoya Kimura Takeshi Miura diff --git a/common/autoware_traffic_light_utils/CHANGELOG.rst b/common/autoware_traffic_light_utils/CHANGELOG.rst index d74774ae8ef3a..518123e826992 100644 --- a/common/autoware_traffic_light_utils/CHANGELOG.rst +++ b/common/autoware_traffic_light_utils/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_traffic_light_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_traffic_light_utils/package.xml b/common/autoware_traffic_light_utils/package.xml index 384839d1c91d4..744a7b08c22a9 100644 --- a/common/autoware_traffic_light_utils/package.xml +++ b/common/autoware_traffic_light_utils/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_utils - 0.38.0 + 0.39.0 The autoware_traffic_light_utils package Kotaro Uetake Shunsuke Miura diff --git a/common/autoware_trajectory/CHANGELOG.rst b/common/autoware_trajectory/CHANGELOG.rst new file mode 100644 index 0000000000000..1fbf18ec57abe --- /dev/null +++ b/common/autoware_trajectory/CHANGELOG.rst @@ -0,0 +1,46 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_trajectory +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.39.0 (2024-11-25) +------------------- +* add changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* feat(autoware_trajectory): change default value of min_points (`#9315 `_) +* fix(autoware_trajectory): fix bug of autoware_trajectory (`#9314 `_) +* feat(autoware_trajectory): change interface of InterpolatedArray (`#9264 `_) + change interface of InterpolateArray +* feat(autoware_trajectory): move trajectory_container from autoware_motion_utils to a new package (`#9253 `_) + * create trajectory container package + * update + * update + * style(pre-commit): autofix + * update codeowner + * update + * fix cmake + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Yukinari Hisaki, Yutaka Kondo + +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* feat(autoware_trajectory): change default value of min_points (`#9315 `_) +* fix(autoware_trajectory): fix bug of autoware_trajectory (`#9314 `_) +* feat(autoware_trajectory): change interface of InterpolatedArray (`#9264 `_) + change interface of InterpolateArray +* feat(autoware_trajectory): move trajectory_container from autoware_motion_utils to a new package (`#9253 `_) + * create trajectory container package + * update + * update + * style(pre-commit): autofix + * update codeowner + * update + * fix cmake + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Yukinari Hisaki, Yutaka Kondo + +0.38.0 (2024-11-11) +------------------- + +0.26.0 (2024-04-03) +------------------- diff --git a/common/autoware_trajectory/package.xml b/common/autoware_trajectory/package.xml index d6ab5465578aa..b1aaaed7efc6b 100644 --- a/common/autoware_trajectory/package.xml +++ b/common/autoware_trajectory/package.xml @@ -2,7 +2,7 @@ autoware_trajectory - 0.1.0 + 0.39.0 The autoware_trajectory package Yukinari Hisaki Takayuki Murooka diff --git a/common/autoware_universe_utils/CHANGELOG.rst b/common/autoware_universe_utils/CHANGELOG.rst index 8d79fbb4f4f2a..c85a9f14e960e 100644 --- a/common/autoware_universe_utils/CHANGELOG.rst +++ b/common/autoware_universe_utils/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package autoware_universe_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_utils): address self-intersecting polygons in random_concave_generator and handle empty inners() during triangulation (`#8995 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Giovanni Muhammad Raditya, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_universe_utils/package.xml b/common/autoware_universe_utils/package.xml index 535206f57c25c..1c2e9993439e4 100644 --- a/common/autoware_universe_utils/package.xml +++ b/common/autoware_universe_utils/package.xml @@ -2,7 +2,7 @@ autoware_universe_utils - 0.38.0 + 0.39.0 The autoware_universe_utils package Takamasa Horibe Takayuki Murooka diff --git a/common/autoware_vehicle_info_utils/CHANGELOG.rst b/common/autoware_vehicle_info_utils/CHANGELOG.rst index 5ad86eddf9f52..4d76f469414b5 100644 --- a/common/autoware_vehicle_info_utils/CHANGELOG.rst +++ b/common/autoware_vehicle_info_utils/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_vehicle_info_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/autoware_vehicle_info_utils/package.xml b/common/autoware_vehicle_info_utils/package.xml index 1e35c8fce516e..bc3f12f5f3ca0 100644 --- a/common/autoware_vehicle_info_utils/package.xml +++ b/common/autoware_vehicle_info_utils/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_info_utils - 0.38.0 + 0.39.0 The autoware_vehicle_info_utils package diff --git a/common/bag_time_manager_rviz_plugin/CHANGELOG.rst b/common/bag_time_manager_rviz_plugin/CHANGELOG.rst index a47ad569440b4..af35aa6921956 100644 --- a/common/bag_time_manager_rviz_plugin/CHANGELOG.rst +++ b/common/bag_time_manager_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package bag_time_manager_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/bag_time_manager_rviz_plugin/package.xml b/common/bag_time_manager_rviz_plugin/package.xml index e9df21b48535f..c3e9895805a12 100644 --- a/common/bag_time_manager_rviz_plugin/package.xml +++ b/common/bag_time_manager_rviz_plugin/package.xml @@ -2,7 +2,7 @@ bag_time_manager_rviz_plugin - 0.38.0 + 0.39.0 Rviz plugin to publish and control the ros bag Taiki Tanaka Apache License 2.0 diff --git a/common/tier4_adapi_rviz_plugin/CHANGELOG.rst b/common/tier4_adapi_rviz_plugin/CHANGELOG.rst index b151eb7f7e06d..ed05abec453cb 100644 --- a/common/tier4_adapi_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_adapi_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_adapi_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_adapi_rviz_plugin/package.xml b/common/tier4_adapi_rviz_plugin/package.xml index c31e19919ff22..97418c7308f5b 100644 --- a/common/tier4_adapi_rviz_plugin/package.xml +++ b/common/tier4_adapi_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_adapi_rviz_plugin - 0.38.0 + 0.39.0 The autoware adapi rviz plugin package Takagi, Isamu Hiroki OTA diff --git a/common/tier4_api_utils/CHANGELOG.rst b/common/tier4_api_utils/CHANGELOG.rst index 3129d35f02c38..a6ac6f3cf1e86 100644 --- a/common/tier4_api_utils/CHANGELOG.rst +++ b/common/tier4_api_utils/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_api_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index 6936fb4034f63..dba6450a338e4 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -2,7 +2,7 @@ tier4_api_utils - 0.38.0 + 0.39.0 The tier4_api_utils package Takagi, Isamu Apache License 2.0 diff --git a/common/tier4_camera_view_rviz_plugin/CHANGELOG.rst b/common/tier4_camera_view_rviz_plugin/CHANGELOG.rst index e71a8d02bd47e..78b243eedcd85 100644 --- a/common/tier4_camera_view_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_camera_view_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_camera_view_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_camera_view_rviz_plugin/package.xml b/common/tier4_camera_view_rviz_plugin/package.xml index 7c85d9f84871a..0728391e2e1ed 100644 --- a/common/tier4_camera_view_rviz_plugin/package.xml +++ b/common/tier4_camera_view_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_camera_view_rviz_plugin - 0.38.0 + 0.39.0 The autoware camera view rviz plugin package Yuxuan Liu Makoto Yabuta diff --git a/common/tier4_datetime_rviz_plugin/CHANGELOG.rst b/common/tier4_datetime_rviz_plugin/CHANGELOG.rst index b8341184faaf7..e5e5a9df7ec7f 100644 --- a/common/tier4_datetime_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_datetime_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_datetime_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_datetime_rviz_plugin/package.xml b/common/tier4_datetime_rviz_plugin/package.xml index ffe95116f9ea3..0a78d7408e3a3 100644 --- a/common/tier4_datetime_rviz_plugin/package.xml +++ b/common/tier4_datetime_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_datetime_rviz_plugin - 0.38.0 + 0.39.0 The tier4_datetime_rviz_plugin package Takagi, Isamu Apache License 2.0 diff --git a/common/tier4_localization_rviz_plugin/CHANGELOG.rst b/common/tier4_localization_rviz_plugin/CHANGELOG.rst index 2a1f10be1ffed..ddbe7b587d9e8 100644 --- a/common/tier4_localization_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_localization_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_localization_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_localization_rviz_plugin/package.xml b/common/tier4_localization_rviz_plugin/package.xml index 29f5b995bce2b..e5623a25416c2 100644 --- a/common/tier4_localization_rviz_plugin/package.xml +++ b/common/tier4_localization_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_localization_rviz_plugin - 0.38.0 + 0.39.0 The tier4_localization_rviz_plugin package Takagi, Isamu Takamasa Horibe diff --git a/common/tier4_planning_rviz_plugin/CHANGELOG.rst b/common/tier4_planning_rviz_plugin/CHANGELOG.rst index c31dc946b12d1..f6ddb9a16283a 100644 --- a/common/tier4_planning_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_planning_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_planning_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_planning_rviz_plugin/package.xml b/common/tier4_planning_rviz_plugin/package.xml index 43641ce361e43..16dedcb450814 100644 --- a/common/tier4_planning_rviz_plugin/package.xml +++ b/common/tier4_planning_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_planning_rviz_plugin - 0.38.0 + 0.39.0 The tier4_planning_rviz_plugin package Yukihiro Saito Takayuki Murooka diff --git a/common/tier4_state_rviz_plugin/CHANGELOG.rst b/common/tier4_state_rviz_plugin/CHANGELOG.rst index 962433de64c70..ac4988a0bff22 100644 --- a/common/tier4_state_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_state_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package tier4_state_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix: missing dependency in common components (`#9072 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo, ぐるぐる + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_state_rviz_plugin/package.xml b/common/tier4_state_rviz_plugin/package.xml index 14ad8a22a52e2..19c8c153b89ee 100644 --- a/common/tier4_state_rviz_plugin/package.xml +++ b/common/tier4_state_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_state_rviz_plugin - 0.38.0 + 0.39.0 The autoware state rviz plugin package Hiroki OTA Takagi, Isamu diff --git a/common/tier4_system_rviz_plugin/CHANGELOG.rst b/common/tier4_system_rviz_plugin/CHANGELOG.rst index 92178542034c4..f5895ae43b3db 100644 --- a/common/tier4_system_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_system_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_system_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_system_rviz_plugin/package.xml b/common/tier4_system_rviz_plugin/package.xml index 6b7b089840537..5e6a30689505f 100644 --- a/common/tier4_system_rviz_plugin/package.xml +++ b/common/tier4_system_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_system_rviz_plugin - 0.38.0 + 0.39.0 The tier4_vehicle_rviz_plugin package Koji Minoda Apache License 2.0 diff --git a/common/tier4_traffic_light_rviz_plugin/CHANGELOG.rst b/common/tier4_traffic_light_rviz_plugin/CHANGELOG.rst index b367a66d0357d..46c123392b23e 100644 --- a/common/tier4_traffic_light_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_traffic_light_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_traffic_light_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_traffic_light_rviz_plugin/package.xml b/common/tier4_traffic_light_rviz_plugin/package.xml index f1e47741e8f0b..6b8718488953a 100644 --- a/common/tier4_traffic_light_rviz_plugin/package.xml +++ b/common/tier4_traffic_light_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_traffic_light_rviz_plugin - 0.38.0 + 0.39.0 The autoware state rviz plugin package Satoshi OTA Apache License 2.0 diff --git a/common/tier4_vehicle_rviz_plugin/CHANGELOG.rst b/common/tier4_vehicle_rviz_plugin/CHANGELOG.rst index b02695f6f8e17..33c59d1d1c93f 100644 --- a/common/tier4_vehicle_rviz_plugin/CHANGELOG.rst +++ b/common/tier4_vehicle_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package tier4_vehicle_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix: missing dependency in common components (`#9072 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo, ぐるぐる + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/common/tier4_vehicle_rviz_plugin/package.xml b/common/tier4_vehicle_rviz_plugin/package.xml index b94f1375cee81..0aee4396e6167 100644 --- a/common/tier4_vehicle_rviz_plugin/package.xml +++ b/common/tier4_vehicle_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_vehicle_rviz_plugin - 0.38.0 + 0.39.0 The tier4_vehicle_rviz_plugin package Yukihiro Saito Apache License 2.0 diff --git a/control/autoware_autonomous_emergency_braking/CHANGELOG.rst b/control/autoware_autonomous_emergency_braking/CHANGELOG.rst index 6e8285c25481d..67fe12fb1243b 100644 --- a/control/autoware_autonomous_emergency_braking/CHANGELOG.rst +++ b/control/autoware_autonomous_emergency_braking/CHANGELOG.rst @@ -2,6 +2,47 @@ Changelog for package autoware_autonomous_emergency_braking ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(control): missing dependency in control components (`#9073 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autonomous_emergency_braking): solve issue with arc length (`#9247 `_) + * solve issue with arc length + * fix problem with points one vehicle apart from path + --------- +* Contributors: Esteve Fernandez, Kem (TiankuiXian), Yutaka Kondo, danielsanchezaran, ぐるぐる + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml index 5fac12cb3e715..bab41a7c634d2 100644 --- a/control/autoware_autonomous_emergency_braking/package.xml +++ b/control/autoware_autonomous_emergency_braking/package.xml @@ -2,7 +2,7 @@ autoware_autonomous_emergency_braking - 0.38.0 + 0.39.0 Autonomous Emergency Braking package as a ROS 2 node Takamasa Horibe Tomoya Kimura diff --git a/control/autoware_collision_detector/CHANGELOG.rst b/control/autoware_collision_detector/CHANGELOG.rst index 3e6f87d08dd6d..4d0f2f9b2c579 100644 --- a/control/autoware_collision_detector/CHANGELOG.rst +++ b/control/autoware_collision_detector/CHANGELOG.rst @@ -2,6 +2,26 @@ Changelog for package autoware_collision_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(collision_detector): skip process when odometry is not published (`#9308 `_) + * subscribe odometry + * fix precommit + * remove unnecessary log info + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(collision_detector): use polling subscriber (`#9213 `_) + use polling subscriber +* Contributors: Esteve Fernandez, Go Sakayori, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_collision_detector/package.xml b/control/autoware_collision_detector/package.xml index ff081e921aef2..e2bdeb7fa9250 100644 --- a/control/autoware_collision_detector/package.xml +++ b/control/autoware_collision_detector/package.xml @@ -2,7 +2,7 @@ autoware_collision_detector - 0.38.0 + 0.39.0 The collision_detector package Kyoichi Sugahara diff --git a/control/autoware_control_validator/CHANGELOG.rst b/control/autoware_control_validator/CHANGELOG.rst index 9b57a109b7780..fca1ed1e51184 100644 --- a/control/autoware_control_validator/CHANGELOG.rst +++ b/control/autoware_control_validator/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_control_validator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(control): missing dependency in control components (`#9073 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo, ぐるぐる + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_control_validator/package.xml b/control/autoware_control_validator/package.xml index fbe759547aba1..24c3daebb6749 100644 --- a/control/autoware_control_validator/package.xml +++ b/control/autoware_control_validator/package.xml @@ -2,7 +2,7 @@ autoware_control_validator - 0.38.0 + 0.39.0 ros node for autoware_control_validator Kyoichi Sugahara Takamasa Horibe diff --git a/control/autoware_external_cmd_selector/CHANGELOG.rst b/control/autoware_external_cmd_selector/CHANGELOG.rst index fee762039a445..85e6e33fae450 100644 --- a/control/autoware_external_cmd_selector/CHANGELOG.rst +++ b/control/autoware_external_cmd_selector/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_external_cmd_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_external_cmd_selector/package.xml b/control/autoware_external_cmd_selector/package.xml index 1d69b4eb8e97e..036e293b308df 100644 --- a/control/autoware_external_cmd_selector/package.xml +++ b/control/autoware_external_cmd_selector/package.xml @@ -2,7 +2,7 @@ autoware_external_cmd_selector - 0.38.0 + 0.39.0 The autoware_external_cmd_selector package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_joy_controller/CHANGELOG.rst b/control/autoware_joy_controller/CHANGELOG.rst index 5e73b2921e356..f0ce6cd9eb030 100644 --- a/control/autoware_joy_controller/CHANGELOG.rst +++ b/control/autoware_joy_controller/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_joy_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_joy_controller/package.xml b/control/autoware_joy_controller/package.xml index 3ee880799a025..3d695f995f855 100644 --- a/control/autoware_joy_controller/package.xml +++ b/control/autoware_joy_controller/package.xml @@ -2,7 +2,7 @@ autoware_joy_controller - 0.38.0 + 0.39.0 The autoware_joy_controller package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_lane_departure_checker/CHANGELOG.rst b/control/autoware_lane_departure_checker/CHANGELOG.rst index 9c8eccb587208..d7f502990a9a2 100644 --- a/control/autoware_lane_departure_checker/CHANGELOG.rst +++ b/control/autoware_lane_departure_checker/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_lane_departure_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(start_planner, lane_departure_checker): speed up by updating polygons (`#9309 `_) + speed up by updating polygons +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo, danielsanchezaran + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_lane_departure_checker/package.xml b/control/autoware_lane_departure_checker/package.xml index c8271f4ef4a6d..70ea7459a2b93 100644 --- a/control/autoware_lane_departure_checker/package.xml +++ b/control/autoware_lane_departure_checker/package.xml @@ -2,7 +2,7 @@ autoware_lane_departure_checker - 0.38.0 + 0.39.0 The autoware_lane_departure_checker package Kyoichi Sugahara Makoto Kurihara diff --git a/control/autoware_mpc_lateral_controller/CHANGELOG.rst b/control/autoware_mpc_lateral_controller/CHANGELOG.rst index 7d32d50b1befd..a361c3aaec161 100644 --- a/control/autoware_mpc_lateral_controller/CHANGELOG.rst +++ b/control/autoware_mpc_lateral_controller/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package autoware_mpc_lateral_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_mpc_lateral_controller): fix bugprone-misplaced-widening-cast (`#9224 `_) + * fix: bugprone-misplaced-widening-cast + * fix: consider negative values + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(mpc_lateral_controller): correctly resample the MPC trajectory yaws (`#9199 `_) +* Contributors: Esteve Fernandez, Maxime CLEMENT, Yutaka Kondo, kobayu858 + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml index a965343ad3e98..d8bb14d211bf8 100644 --- a/control/autoware_mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -2,7 +2,7 @@ autoware_mpc_lateral_controller - 0.38.0 + 0.39.0 MPC-based lateral controller Takamasa Horibe diff --git a/control/autoware_obstacle_collision_checker/CHANGELOG.rst b/control/autoware_obstacle_collision_checker/CHANGELOG.rst index 5cca4c07048b1..05e5b2d4190d7 100644 --- a/control/autoware_obstacle_collision_checker/CHANGELOG.rst +++ b/control/autoware_obstacle_collision_checker/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_obstacle_collision_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_obstacle_collision_checker/package.xml b/control/autoware_obstacle_collision_checker/package.xml index 01200e9c77bc3..66df5e98bf57d 100644 --- a/control/autoware_obstacle_collision_checker/package.xml +++ b/control/autoware_obstacle_collision_checker/package.xml @@ -2,7 +2,7 @@ autoware_obstacle_collision_checker - 0.38.0 + 0.39.0 The obstacle_collision_checker package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_operation_mode_transition_manager/CHANGELOG.rst b/control/autoware_operation_mode_transition_manager/CHANGELOG.rst index 3412c651fc4a7..af99c3781459a 100644 --- a/control/autoware_operation_mode_transition_manager/CHANGELOG.rst +++ b/control/autoware_operation_mode_transition_manager/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_operation_mode_transition_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_operation_mode_transition_manager/package.xml b/control/autoware_operation_mode_transition_manager/package.xml index 98e216a1b96ec..7a0d6977a3e8f 100644 --- a/control/autoware_operation_mode_transition_manager/package.xml +++ b/control/autoware_operation_mode_transition_manager/package.xml @@ -1,6 +1,6 @@ autoware_operation_mode_transition_manager - 0.38.0 + 0.39.0 The operation_mode_transition_manager package Takamasa Horibe Tomoya Kimura diff --git a/control/autoware_pid_longitudinal_controller/CHANGELOG.rst b/control/autoware_pid_longitudinal_controller/CHANGELOG.rst index b246fe3593ad5..57e2ce30aff35 100644 --- a/control/autoware_pid_longitudinal_controller/CHANGELOG.rst +++ b/control/autoware_pid_longitudinal_controller/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_pid_longitudinal_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml index b4bf580e133e7..88f8abaf225e8 100644 --- a/control/autoware_pid_longitudinal_controller/package.xml +++ b/control/autoware_pid_longitudinal_controller/package.xml @@ -2,7 +2,7 @@ autoware_pid_longitudinal_controller - 0.38.0 + 0.39.0 PID-based longitudinal controller Takamasa Horibe diff --git a/control/autoware_pure_pursuit/CHANGELOG.rst b/control/autoware_pure_pursuit/CHANGELOG.rst index 2c60203858a32..df0b7df3a9e52 100644 --- a/control/autoware_pure_pursuit/CHANGELOG.rst +++ b/control/autoware_pure_pursuit/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_pure_pursuit ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_pure_pursuit): fix cppcheck unusedFunction (`#9276 `_) +* Contributors: Esteve Fernandez, Ryuta Kambe, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_pure_pursuit/package.xml b/control/autoware_pure_pursuit/package.xml index 55fdac624f0d7..03c46dbc22bb6 100644 --- a/control/autoware_pure_pursuit/package.xml +++ b/control/autoware_pure_pursuit/package.xml @@ -2,7 +2,7 @@ autoware_pure_pursuit - 0.38.0 + 0.39.0 The pure_pursuit package Takamasa Horibe Takayuki Murooka diff --git a/control/autoware_shift_decider/CHANGELOG.rst b/control/autoware_shift_decider/CHANGELOG.rst index 032398006ac94..72257774b4763 100644 --- a/control/autoware_shift_decider/CHANGELOG.rst +++ b/control/autoware_shift_decider/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_shift_decider ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_shift_decider/package.xml b/control/autoware_shift_decider/package.xml index f63b811d2eaf9..75b11dfcd8379 100644 --- a/control/autoware_shift_decider/package.xml +++ b/control/autoware_shift_decider/package.xml @@ -2,7 +2,7 @@ autoware_shift_decider - 0.38.0 + 0.39.0 The autoware_shift_decider package Takamasa Horibe Takayuki Murooka diff --git a/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst b/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst index ab53787cae6e0..34bb120a2752c 100644 --- a/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst +++ b/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_smart_mpc_trajectory_follower ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_smart_mpc_trajectory_follower/package.xml b/control/autoware_smart_mpc_trajectory_follower/package.xml index ca8331eaae9a9..fb70eb05d21e5 100644 --- a/control/autoware_smart_mpc_trajectory_follower/package.xml +++ b/control/autoware_smart_mpc_trajectory_follower/package.xml @@ -2,7 +2,7 @@ autoware_smart_mpc_trajectory_follower - 0.38.0 + 0.39.0 Nodes to follow a trajectory by generating control commands using smart mpc diff --git a/control/autoware_trajectory_follower_base/CHANGELOG.rst b/control/autoware_trajectory_follower_base/CHANGELOG.rst index 9b52928f063bd..9182dabfe66a6 100644 --- a/control/autoware_trajectory_follower_base/CHANGELOG.rst +++ b/control/autoware_trajectory_follower_base/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_trajectory_follower_base ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_trajectory_follower_base/package.xml b/control/autoware_trajectory_follower_base/package.xml index 663648950258c..32bf2b1f1a809 100644 --- a/control/autoware_trajectory_follower_base/package.xml +++ b/control/autoware_trajectory_follower_base/package.xml @@ -2,7 +2,7 @@ autoware_trajectory_follower_base - 0.38.0 + 0.39.0 Library for generating lateral and longitudinal controls following a trajectory diff --git a/control/autoware_trajectory_follower_node/CHANGELOG.rst b/control/autoware_trajectory_follower_node/CHANGELOG.rst index cda983ab27d89..fad7a121bb624 100644 --- a/control/autoware_trajectory_follower_node/CHANGELOG.rst +++ b/control/autoware_trajectory_follower_node/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_trajectory_follower_node ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(control): missing dependency in control components (`#9073 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo, ぐるぐる + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_trajectory_follower_node/package.xml b/control/autoware_trajectory_follower_node/package.xml index 86a2592ebf5f4..e4000feef9474 100644 --- a/control/autoware_trajectory_follower_node/package.xml +++ b/control/autoware_trajectory_follower_node/package.xml @@ -2,7 +2,7 @@ autoware_trajectory_follower_node - 0.38.0 + 0.39.0 Nodes to follow a trajectory by generating control commands separated into lateral and longitudinal commands diff --git a/control/autoware_vehicle_cmd_gate/CHANGELOG.rst b/control/autoware_vehicle_cmd_gate/CHANGELOG.rst index 20fc77c4cda55..ce6420fa69b76 100644 --- a/control/autoware_vehicle_cmd_gate/CHANGELOG.rst +++ b/control/autoware_vehicle_cmd_gate/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package autoware_vehicle_cmd_gate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(control): missing dependency in control components (`#9073 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(vehicle_cmd_gate): fix processing time measurement (`#9260 `_) +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Maxime CLEMENT, Yutaka Kondo, ぐるぐる + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/autoware_vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml index a5026a0edb3ef..3253f5a498933 100644 --- a/control/autoware_vehicle_cmd_gate/package.xml +++ b/control/autoware_vehicle_cmd_gate/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_cmd_gate - 0.38.0 + 0.39.0 The vehicle_cmd_gate package Takamasa Horibe Tomoya Kimura diff --git a/control/control_performance_analysis/CHANGELOG.rst b/control/control_performance_analysis/CHANGELOG.rst index cfe98a0e66275..f32fbe5cb0b1c 100644 --- a/control/control_performance_analysis/CHANGELOG.rst +++ b/control/control_performance_analysis/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package control_performance_analysis ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/control_performance_analysis/package.xml b/control/control_performance_analysis/package.xml index 203357d3f0474..49b8f69570bb4 100644 --- a/control/control_performance_analysis/package.xml +++ b/control/control_performance_analysis/package.xml @@ -2,7 +2,7 @@ control_performance_analysis - 0.38.0 + 0.39.0 Controller Performance Evaluation Berkay Karaman Taiki Tanaka diff --git a/control/predicted_path_checker/CHANGELOG.rst b/control/predicted_path_checker/CHANGELOG.rst index b2dbfa706eedc..15418d84cba3a 100644 --- a/control/predicted_path_checker/CHANGELOG.rst +++ b/control/predicted_path_checker/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package predicted_path_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/control/predicted_path_checker/package.xml b/control/predicted_path_checker/package.xml index cfa2a23be92da..f23828f8a586c 100644 --- a/control/predicted_path_checker/package.xml +++ b/control/predicted_path_checker/package.xml @@ -2,7 +2,7 @@ predicted_path_checker - 0.38.0 + 0.39.0 The predicted_path_checker package Berkay Karaman diff --git a/evaluator/autoware_control_evaluator/CHANGELOG.rst b/evaluator/autoware_control_evaluator/CHANGELOG.rst index 2469aea0deca1..e67a53de4656a 100644 --- a/evaluator/autoware_control_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_control_evaluator/CHANGELOG.rst @@ -2,6 +2,46 @@ Changelog for package autoware_control_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* test(autoware_control_evaluator): add unit test for utils autoware_control_evaluator (`#9307 `_) + * update unit test of control_evaluator. + * manual pre-commit. + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Kem (TiankuiXian), Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/evaluator/autoware_control_evaluator/package.xml b/evaluator/autoware_control_evaluator/package.xml index 1c724fc7bd0ec..473f3bff7257e 100644 --- a/evaluator/autoware_control_evaluator/package.xml +++ b/evaluator/autoware_control_evaluator/package.xml @@ -2,7 +2,7 @@ autoware_control_evaluator - 0.38.0 + 0.39.0 ROS 2 node for evaluating control Daniel SANCHEZ takayuki MUROOKA diff --git a/evaluator/autoware_planning_evaluator/CHANGELOG.rst b/evaluator/autoware_planning_evaluator/CHANGELOG.rst index cf4aaf2e7fc94..9dc854ae8d623 100644 --- a/evaluator/autoware_planning_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_planning_evaluator/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package autoware_planning_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Kem (TiankuiXian), Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/evaluator/autoware_planning_evaluator/package.xml b/evaluator/autoware_planning_evaluator/package.xml index 827784f71a823..09c8a17a8d791 100644 --- a/evaluator/autoware_planning_evaluator/package.xml +++ b/evaluator/autoware_planning_evaluator/package.xml @@ -2,7 +2,7 @@ autoware_planning_evaluator - 0.38.0 + 0.39.0 ROS 2 node for evaluating planners Maxime CLEMENT Kyoichi Sugahara diff --git a/evaluator/kinematic_evaluator/CHANGELOG.rst b/evaluator/kinematic_evaluator/CHANGELOG.rst index ceacbcf0b129d..da5509f14143e 100644 --- a/evaluator/kinematic_evaluator/CHANGELOG.rst +++ b/evaluator/kinematic_evaluator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package kinematic_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/evaluator/kinematic_evaluator/package.xml b/evaluator/kinematic_evaluator/package.xml index 99254d06d0642..ab01f15c3c154 100644 --- a/evaluator/kinematic_evaluator/package.xml +++ b/evaluator/kinematic_evaluator/package.xml @@ -1,7 +1,7 @@ kinematic_evaluator - 0.38.0 + 0.39.0 kinematic evaluator ROS 2 node Dominik Jargot diff --git a/evaluator/localization_evaluator/CHANGELOG.rst b/evaluator/localization_evaluator/CHANGELOG.rst index 62f63139999e2..7438643fe19a6 100644 --- a/evaluator/localization_evaluator/CHANGELOG.rst +++ b/evaluator/localization_evaluator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package localization_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/evaluator/localization_evaluator/package.xml b/evaluator/localization_evaluator/package.xml index b9d6285a0f08c..a38871a1af6a2 100644 --- a/evaluator/localization_evaluator/package.xml +++ b/evaluator/localization_evaluator/package.xml @@ -1,7 +1,7 @@ localization_evaluator - 0.38.0 + 0.39.0 localization evaluator ROS 2 node Dominik Jargot diff --git a/evaluator/perception_online_evaluator/CHANGELOG.rst b/evaluator/perception_online_evaluator/CHANGELOG.rst index 643dec851d0fa..f3e999f66ee0e 100644 --- a/evaluator/perception_online_evaluator/CHANGELOG.rst +++ b/evaluator/perception_online_evaluator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package perception_online_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/perception_online_evaluator/package.xml index 1e7c0a7d128e6..bebc46457807e 100644 --- a/evaluator/perception_online_evaluator/package.xml +++ b/evaluator/perception_online_evaluator/package.xml @@ -2,7 +2,7 @@ perception_online_evaluator - 0.38.0 + 0.39.0 ROS 2 node for evaluating perception Fumiya Watanabe Kosuke Takeuchi diff --git a/evaluator/scenario_simulator_v2_adapter/package.xml b/evaluator/scenario_simulator_v2_adapter/package.xml index ae6b49671a774..45c4f91c0eb83 100644 --- a/evaluator/scenario_simulator_v2_adapter/package.xml +++ b/evaluator/scenario_simulator_v2_adapter/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2_adapter - 0.5.6 + 0.39.0 Node for converting autoware's messages into UserDefinedValue messages Kyoichi Sugahara Maxime CLEMENT diff --git a/launch/tier4_autoware_api_launch/CHANGELOG.rst b/launch/tier4_autoware_api_launch/CHANGELOG.rst index c4dc5fba123fb..38825528d8c39 100644 --- a/launch/tier4_autoware_api_launch/CHANGELOG.rst +++ b/launch/tier4_autoware_api_launch/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_autoware_api_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_autoware_api_launch/package.xml b/launch/tier4_autoware_api_launch/package.xml index 2af274907306a..4b52acbc8d804 100644 --- a/launch/tier4_autoware_api_launch/package.xml +++ b/launch/tier4_autoware_api_launch/package.xml @@ -2,7 +2,7 @@ tier4_autoware_api_launch - 0.38.0 + 0.39.0 The tier4_autoware_api_launch package Takagi, Isamu Ryohsuke Mitsudome diff --git a/launch/tier4_control_launch/CHANGELOG.rst b/launch/tier4_control_launch/CHANGELOG.rst index 11f7420e9e513..cbe41dcd85828 100644 --- a/launch/tier4_control_launch/CHANGELOG.rst +++ b/launch/tier4_control_launch/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package tier4_control_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(collision_detector): skip process when odometry is not published (`#9308 `_) + * subscribe odometry + * fix precommit + * remove unnecessary log info + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(aeb): set global param to override autoware state check (`#9263 `_) + * set global param to override autoware state check + * change variable to be more general + * add comment + * move param to control component launch + * change param name to be more straightforward + --------- +* feat(control_launch): add collision detector in launch (`#9214 `_) + add collision detector in launch +* Contributors: Esteve Fernandez, Go Sakayori, Yutaka Kondo, danielsanchezaran + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index a6a57e0b02716..09eb3302c7811 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -2,7 +2,7 @@ tier4_control_launch - 0.38.0 + 0.39.0 The tier4_control_launch package Takamasa Horibe Takayuki Murooka diff --git a/launch/tier4_localization_launch/CHANGELOG.rst b/launch/tier4_localization_launch/CHANGELOG.rst index b7d0b8cf8169d..21cf37981a40a 100644 --- a/launch/tier4_localization_launch/CHANGELOG.rst +++ b/launch/tier4_localization_launch/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_localization_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 89627ad420afc..66d2a3277f505 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -2,7 +2,7 @@ tier4_localization_launch - 0.38.0 + 0.39.0 The tier4_localization_launch package Yamato Ando Kento Yabuuchi diff --git a/launch/tier4_map_launch/CHANGELOG.rst b/launch/tier4_map_launch/CHANGELOG.rst index e1ee86c71fc15..11f8aeb97cda3 100644 --- a/launch/tier4_map_launch/CHANGELOG.rst +++ b/launch/tier4_map_launch/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_map_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index a5120987605f5..91874321b5db0 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -2,7 +2,7 @@ tier4_map_launch - 0.38.0 + 0.39.0 The tier4_map_launch package Ryu Yamamoto Kento Yabuuchi diff --git a/launch/tier4_perception_launch/CHANGELOG.rst b/launch/tier4_perception_launch/CHANGELOG.rst index b0cb6c69d6892..412665dab796f 100644 --- a/launch/tier4_perception_launch/CHANGELOG.rst +++ b/launch/tier4_perception_launch/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_perception_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 22c664b998a2c..7b705d4b74f78 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -2,7 +2,7 @@ tier4_perception_launch - 0.38.0 + 0.39.0 The tier4_perception_launch package Yukihiro Saito Shunsuke Miura diff --git a/launch/tier4_planning_launch/CHANGELOG.rst b/launch/tier4_planning_launch/CHANGELOG.rst index c66ad480472ca..2641162594a74 100644 --- a/launch/tier4_planning_launch/CHANGELOG.rst +++ b/launch/tier4_planning_launch/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_planning_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 7f181d6d707b6..286e09a2f17ed 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -2,7 +2,7 @@ tier4_planning_launch - 0.38.0 + 0.39.0 The tier4_planning_launch package diff --git a/launch/tier4_sensing_launch/CHANGELOG.rst b/launch/tier4_sensing_launch/CHANGELOG.rst index be5bb4dd8fce6..7e1b9756effdd 100644 --- a/launch/tier4_sensing_launch/CHANGELOG.rst +++ b/launch/tier4_sensing_launch/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_sensing_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_sensing_launch/package.xml b/launch/tier4_sensing_launch/package.xml index d4e03219b2299..12194a163e0f1 100644 --- a/launch/tier4_sensing_launch/package.xml +++ b/launch/tier4_sensing_launch/package.xml @@ -2,7 +2,7 @@ tier4_sensing_launch - 0.38.0 + 0.39.0 The tier4_sensing_launch package Yukihiro Saito Apache License 2.0 diff --git a/launch/tier4_simulator_launch/CHANGELOG.rst b/launch/tier4_simulator_launch/CHANGELOG.rst index 14927284d98a7..46aa2059dea76 100644 --- a/launch/tier4_simulator_launch/CHANGELOG.rst +++ b/launch/tier4_simulator_launch/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package tier4_simulator_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Kem (TiankuiXian), Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_simulator_launch/package.xml b/launch/tier4_simulator_launch/package.xml index 6452241dc3f72..b61954dcc297d 100644 --- a/launch/tier4_simulator_launch/package.xml +++ b/launch/tier4_simulator_launch/package.xml @@ -2,7 +2,7 @@ tier4_simulator_launch - 0.38.0 + 0.39.0 The tier4_simulator_launch package Keisuke Shima Takayuki Murooka diff --git a/launch/tier4_system_launch/CHANGELOG.rst b/launch/tier4_system_launch/CHANGELOG.rst index d42dea8eb7b24..26f1031652d54 100644 --- a/launch/tier4_system_launch/CHANGELOG.rst +++ b/launch/tier4_system_launch/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_system_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_system_launch/package.xml b/launch/tier4_system_launch/package.xml index 6d335269f734d..92bee6d1d3e86 100644 --- a/launch/tier4_system_launch/package.xml +++ b/launch/tier4_system_launch/package.xml @@ -2,7 +2,7 @@ tier4_system_launch - 0.38.0 + 0.39.0 The tier4_system_launch package Fumihito Ito TetsuKawa diff --git a/launch/tier4_vehicle_launch/CHANGELOG.rst b/launch/tier4_vehicle_launch/CHANGELOG.rst index dfd9f0759abfc..4823ed84f46f6 100644 --- a/launch/tier4_vehicle_launch/CHANGELOG.rst +++ b/launch/tier4_vehicle_launch/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package tier4_vehicle_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/launch/tier4_vehicle_launch/package.xml b/launch/tier4_vehicle_launch/package.xml index 9a8c03c62a7b3..ab3e7483c8593 100644 --- a/launch/tier4_vehicle_launch/package.xml +++ b/launch/tier4_vehicle_launch/package.xml @@ -2,7 +2,7 @@ tier4_vehicle_launch - 0.38.0 + 0.39.0 The tier4_vehicle_launch package Yukihiro Saito Apache License 2.0 diff --git a/localization/autoware_ekf_localizer/CHANGELOG.rst b/localization/autoware_ekf_localizer/CHANGELOG.rst index bce88cb58f6c5..369a731d87ee6 100644 --- a/localization/autoware_ekf_localizer/CHANGELOG.rst +++ b/localization/autoware_ekf_localizer/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_ekf_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_ekf_localizer): remove `timer_tf\_` (`#9244 `_) + Removed timer_tf\_ +* Contributors: Esteve Fernandez, SakodaShintaro, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_ekf_localizer/package.xml b/localization/autoware_ekf_localizer/package.xml index c9abefcd5e849..d93b4eb1ff016 100644 --- a/localization/autoware_ekf_localizer/package.xml +++ b/localization/autoware_ekf_localizer/package.xml @@ -2,7 +2,7 @@ autoware_ekf_localizer - 0.38.0 + 0.39.0 The autoware_ekf_localizer package Takamasa Horibe Yamato Ando diff --git a/localization/autoware_geo_pose_projector/CHANGELOG.rst b/localization/autoware_geo_pose_projector/CHANGELOG.rst index 41729bbef184c..717118a5c1692 100644 --- a/localization/autoware_geo_pose_projector/CHANGELOG.rst +++ b/localization/autoware_geo_pose_projector/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_geo_pose_projector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_geo_pose_projector/package.xml b/localization/autoware_geo_pose_projector/package.xml index 7425b964a0d5d..4fecd89630e01 100644 --- a/localization/autoware_geo_pose_projector/package.xml +++ b/localization/autoware_geo_pose_projector/package.xml @@ -2,7 +2,7 @@ autoware_geo_pose_projector - 0.38.0 + 0.39.0 The autoware_geo_pose_projector package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_gyro_odometer/CHANGELOG.rst b/localization/autoware_gyro_odometer/CHANGELOG.rst index b2a293af33018..950fd01b2ce6f 100644 --- a/localization/autoware_gyro_odometer/CHANGELOG.rst +++ b/localization/autoware_gyro_odometer/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_gyro_odometer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_gyro_odometer/package.xml b/localization/autoware_gyro_odometer/package.xml index 41626e3f8c70b..b546312ef729e 100644 --- a/localization/autoware_gyro_odometer/package.xml +++ b/localization/autoware_gyro_odometer/package.xml @@ -2,7 +2,7 @@ autoware_gyro_odometer - 0.38.0 + 0.39.0 The autoware_gyro_odometer package as a ROS 2 node Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst index d74b537c50fdd..e8cc6d9f2796e 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_ar_tag_based_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml index 4ff6c0c9ca9b1..c0ee5cf973001 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml @@ -2,7 +2,7 @@ autoware_ar_tag_based_localizer - 0.38.0 + 0.39.0 The autoware_ar_tag_based_localizer package Shintaro Sakoda Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst index 1c08781d5e233..e50f441c27ca5 100644 --- a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_landmark_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml index a5250d6c81afc..357fc2b9eb32c 100644 --- a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml @@ -2,7 +2,7 @@ autoware_landmark_manager - 0.38.0 + 0.39.0 The autoware_landmark_manager package Shintaro Sakoda Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst index 4d154f8e365f9..374bdd1f09901 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_lidar_marker_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml index 91976ab1a74e1..72bded6b2b416 100755 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml @@ -2,7 +2,7 @@ autoware_lidar_marker_localizer - 0.38.0 + 0.39.0 The autoware_lidar_marker_localizer package Yamato Ando Shintaro Sakoda diff --git a/localization/autoware_localization_error_monitor/CHANGELOG.rst b/localization/autoware_localization_error_monitor/CHANGELOG.rst index d24c1d7ac4bce..ba263d0f8cb42 100644 --- a/localization/autoware_localization_error_monitor/CHANGELOG.rst +++ b/localization/autoware_localization_error_monitor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_localization_error_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_localization_error_monitor/package.xml b/localization/autoware_localization_error_monitor/package.xml index e07445b878d9c..937d4e71bc717 100644 --- a/localization/autoware_localization_error_monitor/package.xml +++ b/localization/autoware_localization_error_monitor/package.xml @@ -2,7 +2,7 @@ autoware_localization_error_monitor - 0.38.0 + 0.39.0 ros node for monitoring localization error Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_localization_util/CHANGELOG.rst b/localization/autoware_localization_util/CHANGELOG.rst index 7dae713216362..d029d05144595 100644 --- a/localization/autoware_localization_util/CHANGELOG.rst +++ b/localization/autoware_localization_util/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_localization_util ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_localization_util/package.xml b/localization/autoware_localization_util/package.xml index 49330e04c8b2f..ea22ffe59ce64 100644 --- a/localization/autoware_localization_util/package.xml +++ b/localization/autoware_localization_util/package.xml @@ -2,7 +2,7 @@ autoware_localization_util - 0.38.0 + 0.39.0 The autoware_localization_util package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_ndt_scan_matcher/CHANGELOG.rst b/localization/autoware_ndt_scan_matcher/CHANGELOG.rst index 36b7becac9be0..096804e155328 100644 --- a/localization/autoware_ndt_scan_matcher/CHANGELOG.rst +++ b/localization/autoware_ndt_scan_matcher/CHANGELOG.rst @@ -2,6 +2,56 @@ Changelog for package autoware_ndt_scan_matcher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* perf(autoware_ndt_scan_matcher): remove evecs\_, evals\_ of Leaf for memory efficiency (`#9281 `_) + * fix(lane_change): correct computation of maximum lane changing length threshold (`#9279 `_) + fix computation of maximum lane changing length threshold + * perf: remove evecs, evals from Leaf + * perf: remove evecs, evals from Leaf + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_ndt_scan_matcher): fix cppcheck unusedFunction (`#9275 `_) +* fix(autoware_ndt_scan_matcher): reduce initial_pose_estimation.particles_num from 200 to 100 on tests (`#9218 `_) + Reduced initial_pose_estimation.particles_num from 200 to 100 on tests +* refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (`#8912 `_) + * Moved ndt_omp into ndt_scan_matcher + * Added Copyright + * style(pre-commit): autofix + * Fixed include + * Fixed cast style + * Fixed include + * Fixed honorific title + * Fixed honorific title + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed hierarchy + * Fixed NVTP to NVTL + * Added cspell:ignore + * Fixed miss spell + * style(pre-commit): autofix + * Fixed include + * Renamed applyFilter + * Moved ***_impl.hpp from include/ to src/ + * style(pre-commit): autofix + * Fixed variable scope + * Fixed to pass by reference + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Kento Osa, Ryuta Kambe, SakodaShintaro, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_ndt_scan_matcher/package.xml b/localization/autoware_ndt_scan_matcher/package.xml index 9e5b3dabbbc27..96c73f248a595 100644 --- a/localization/autoware_ndt_scan_matcher/package.xml +++ b/localization/autoware_ndt_scan_matcher/package.xml @@ -2,7 +2,7 @@ autoware_ndt_scan_matcher - 0.38.0 + 0.39.0 The autoware_ndt_scan_matcher package Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_pose2twist/CHANGELOG.rst b/localization/autoware_pose2twist/CHANGELOG.rst index 653daf8d9a34c..dcabfddfd2256 100644 --- a/localization/autoware_pose2twist/CHANGELOG.rst +++ b/localization/autoware_pose2twist/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_pose2twist ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_pose2twist/package.xml b/localization/autoware_pose2twist/package.xml index 74ae9b8a10de7..9e7ec378c8570 100644 --- a/localization/autoware_pose2twist/package.xml +++ b/localization/autoware_pose2twist/package.xml @@ -2,7 +2,7 @@ autoware_pose2twist - 0.38.0 + 0.39.0 The autoware_pose2twist package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_pose_covariance_modifier/CHANGELOG.rst b/localization/autoware_pose_covariance_modifier/CHANGELOG.rst index e59dee39371e3..b3c5fdc70f36a 100644 --- a/localization/autoware_pose_covariance_modifier/CHANGELOG.rst +++ b/localization/autoware_pose_covariance_modifier/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_pose_covariance_modifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_pose_covariance_modifier/package.xml b/localization/autoware_pose_covariance_modifier/package.xml index 2c0f9ae142370..2490fdc43dc0a 100644 --- a/localization/autoware_pose_covariance_modifier/package.xml +++ b/localization/autoware_pose_covariance_modifier/package.xml @@ -2,7 +2,7 @@ autoware_pose_covariance_modifier - 0.38.0 + 0.39.0 Add a description. Melike Tanrikulu diff --git a/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst b/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst index 37bf54b3d27ee..423a73677c311 100644 --- a/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst +++ b/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_pose_estimator_arbiter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_pose_estimator_arbiter/package.xml b/localization/autoware_pose_estimator_arbiter/package.xml index adf90c534ef8f..cf30e8fcb5ef6 100644 --- a/localization/autoware_pose_estimator_arbiter/package.xml +++ b/localization/autoware_pose_estimator_arbiter/package.xml @@ -2,7 +2,7 @@ autoware_pose_estimator_arbiter - 0.38.0 + 0.39.0 The arbiter of multiple pose estimators Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_pose_initializer/CHANGELOG.rst b/localization/autoware_pose_initializer/CHANGELOG.rst index c6986a26a3d20..ca509039af804 100644 --- a/localization/autoware_pose_initializer/CHANGELOG.rst +++ b/localization/autoware_pose_initializer/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_pose_initializer/package.xml b/localization/autoware_pose_initializer/package.xml index 99e2c55c312f2..e23a319e2ac2b 100644 --- a/localization/autoware_pose_initializer/package.xml +++ b/localization/autoware_pose_initializer/package.xml @@ -2,7 +2,7 @@ autoware_pose_initializer - 0.38.0 + 0.39.0 The autoware_pose_initializer package Yamato Ando Takagi, Isamu diff --git a/localization/autoware_pose_instability_detector/CHANGELOG.rst b/localization/autoware_pose_instability_detector/CHANGELOG.rst index f81c3c36e8b90..a02f1443d97e1 100644 --- a/localization/autoware_pose_instability_detector/CHANGELOG.rst +++ b/localization/autoware_pose_instability_detector/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_pose_instability_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_pose_instability_detector/package.xml b/localization/autoware_pose_instability_detector/package.xml index d3d7cc81166b6..2c982e30ca8d8 100644 --- a/localization/autoware_pose_instability_detector/package.xml +++ b/localization/autoware_pose_instability_detector/package.xml @@ -2,7 +2,7 @@ autoware_pose_instability_detector - 0.38.0 + 0.39.0 The autoware_pose_instability_detector package Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_stop_filter/CHANGELOG.rst b/localization/autoware_stop_filter/CHANGELOG.rst index 94aa8719318f5..30e5b6169c154 100644 --- a/localization/autoware_stop_filter/CHANGELOG.rst +++ b/localization/autoware_stop_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_stop_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_stop_filter/package.xml b/localization/autoware_stop_filter/package.xml index 499cb49af41a5..07ad7288c9d63 100644 --- a/localization/autoware_stop_filter/package.xml +++ b/localization/autoware_stop_filter/package.xml @@ -2,7 +2,7 @@ autoware_stop_filter - 0.38.0 + 0.39.0 The stop filter package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_twist2accel/CHANGELOG.rst b/localization/autoware_twist2accel/CHANGELOG.rst index 1f6228b9b5f62..ea50813677005 100644 --- a/localization/autoware_twist2accel/CHANGELOG.rst +++ b/localization/autoware_twist2accel/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_twist2accel ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/autoware_twist2accel/package.xml b/localization/autoware_twist2accel/package.xml index ac40f9b43bc90..538a75f8f9474 100644 --- a/localization/autoware_twist2accel/package.xml +++ b/localization/autoware_twist2accel/package.xml @@ -2,7 +2,7 @@ autoware_twist2accel - 0.38.0 + 0.39.0 The acceleration estimation package Yamato Ando Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_common/CHANGELOG.rst b/localization/yabloc/yabloc_common/CHANGELOG.rst index 936f230220d86..7cdbceeb5a6a5 100644 --- a/localization/yabloc/yabloc_common/CHANGELOG.rst +++ b/localization/yabloc/yabloc_common/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package yabloc_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index 7bcf4084073c4..01b5a92745c3f 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -1,7 +1,7 @@ yabloc_common - 0.38.0 + 0.39.0 YabLoc common library Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_image_processing/CHANGELOG.rst b/localization/yabloc/yabloc_image_processing/CHANGELOG.rst index b3b0eab9847b4..f6e619c8a62a6 100644 --- a/localization/yabloc/yabloc_image_processing/CHANGELOG.rst +++ b/localization/yabloc/yabloc_image_processing/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package yabloc_image_processing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/yabloc/yabloc_image_processing/package.xml b/localization/yabloc/yabloc_image_processing/package.xml index 4dc13b1f923e2..746e01f8e9841 100644 --- a/localization/yabloc/yabloc_image_processing/package.xml +++ b/localization/yabloc/yabloc_image_processing/package.xml @@ -2,7 +2,7 @@ yabloc_image_processing - 0.38.0 + 0.39.0 YabLoc image processing package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_monitor/CHANGELOG.rst b/localization/yabloc/yabloc_monitor/CHANGELOG.rst index 322ed6fa7ce20..ea890d490ccfb 100644 --- a/localization/yabloc/yabloc_monitor/CHANGELOG.rst +++ b/localization/yabloc/yabloc_monitor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package yabloc_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/yabloc/yabloc_monitor/package.xml b/localization/yabloc/yabloc_monitor/package.xml index 9fd3e2af75625..ea7ce24f5da7c 100644 --- a/localization/yabloc/yabloc_monitor/package.xml +++ b/localization/yabloc/yabloc_monitor/package.xml @@ -2,7 +2,7 @@ yabloc_monitor - 0.38.0 + 0.39.0 YabLoc monitor package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst b/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst index 967571100c5f4..973e729089d7b 100644 --- a/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst +++ b/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package yabloc_particle_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/yabloc/yabloc_particle_filter/package.xml b/localization/yabloc/yabloc_particle_filter/package.xml index cbf19be65148f..ac5ba4d30bb8a 100644 --- a/localization/yabloc/yabloc_particle_filter/package.xml +++ b/localization/yabloc/yabloc_particle_filter/package.xml @@ -2,7 +2,7 @@ yabloc_particle_filter - 0.38.0 + 0.39.0 YabLoc particle filter package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst b/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst index fac49c978ca92..2bae9b010e7f0 100644 --- a/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst +++ b/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package yabloc_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/localization/yabloc/yabloc_pose_initializer/package.xml b/localization/yabloc/yabloc_pose_initializer/package.xml index 4e650340a309f..77fc397d207d4 100644 --- a/localization/yabloc/yabloc_pose_initializer/package.xml +++ b/localization/yabloc/yabloc_pose_initializer/package.xml @@ -1,7 +1,7 @@ yabloc_pose_initializer - 0.38.0 + 0.39.0 The pose initializer Kento Yabuuchi Masahiro Sakamoto diff --git a/map/autoware_map_height_fitter/CHANGELOG.rst b/map/autoware_map_height_fitter/CHANGELOG.rst index 5521960cabbdf..724ca70e2ec2d 100644 --- a/map/autoware_map_height_fitter/CHANGELOG.rst +++ b/map/autoware_map_height_fitter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_map_height_fitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/map/autoware_map_height_fitter/package.xml b/map/autoware_map_height_fitter/package.xml index bfb9855320d4b..280ad1797a079 100644 --- a/map/autoware_map_height_fitter/package.xml +++ b/map/autoware_map_height_fitter/package.xml @@ -2,7 +2,7 @@ autoware_map_height_fitter - 0.38.0 + 0.39.0 The autoware_map_height_fitter package Takagi, Isamu Yamato Ando diff --git a/map/autoware_map_loader/CHANGELOG.rst b/map/autoware_map_loader/CHANGELOG.rst index 8aafae5e8b44b..876670b13ca3d 100644 --- a/map/autoware_map_loader/CHANGELOG.rst +++ b/map/autoware_map_loader/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_map_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/map/autoware_map_loader/package.xml b/map/autoware_map_loader/package.xml index 7b793359d725b..48e3b6efdaa13 100644 --- a/map/autoware_map_loader/package.xml +++ b/map/autoware_map_loader/package.xml @@ -2,7 +2,7 @@ autoware_map_loader - 0.38.0 + 0.39.0 The autoware_map_loader package Yamato Ando Ryu Yamamoto diff --git a/map/autoware_map_projection_loader/CHANGELOG.rst b/map/autoware_map_projection_loader/CHANGELOG.rst index 40041fa24cda2..b0e85cc682510 100644 --- a/map/autoware_map_projection_loader/CHANGELOG.rst +++ b/map/autoware_map_projection_loader/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_map_projection_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/map/autoware_map_projection_loader/package.xml b/map/autoware_map_projection_loader/package.xml index ddf95efc7414c..7ce0cbb8105a7 100644 --- a/map/autoware_map_projection_loader/package.xml +++ b/map/autoware_map_projection_loader/package.xml @@ -2,7 +2,7 @@ autoware_map_projection_loader - 0.38.0 + 0.39.0 autoware_map_projection_loader package as a ROS 2 node Yamato Ando Masahiro Sakamoto diff --git a/map/autoware_map_tf_generator/CHANGELOG.rst b/map/autoware_map_tf_generator/CHANGELOG.rst index d8c2ebdd75145..18bde0c6a0106 100644 --- a/map/autoware_map_tf_generator/CHANGELOG.rst +++ b/map/autoware_map_tf_generator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_map_tf_generator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/map/autoware_map_tf_generator/package.xml b/map/autoware_map_tf_generator/package.xml index 3c6de9333de79..9a5e0388e08b9 100644 --- a/map/autoware_map_tf_generator/package.xml +++ b/map/autoware_map_tf_generator/package.xml @@ -2,7 +2,7 @@ autoware_map_tf_generator - 0.38.0 + 0.39.0 map_tf_generator package as a ROS 2 node Yamato Ando Kento Yabuuchi diff --git a/perception/autoware_bytetrack/CHANGELOG.rst b/perception/autoware_bytetrack/CHANGELOG.rst index 2c30ebf81ee43..7b18570598431 100644 --- a/perception/autoware_bytetrack/CHANGELOG.rst +++ b/perception/autoware_bytetrack/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_bytetrack ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_bytetrack/package.xml b/perception/autoware_bytetrack/package.xml index d087f22c53374..0cb0747fff40a 100644 --- a/perception/autoware_bytetrack/package.xml +++ b/perception/autoware_bytetrack/package.xml @@ -2,7 +2,7 @@ autoware_bytetrack - 0.38.0 + 0.39.0 ByteTrack implementation ported toward Autoware Manato HIRABAYASHI Yoshi RI diff --git a/perception/autoware_cluster_merger/CHANGELOG.rst b/perception/autoware_cluster_merger/CHANGELOG.rst index a304c9a878d5d..9e1d2b9d0caff 100644 --- a/perception/autoware_cluster_merger/CHANGELOG.rst +++ b/perception/autoware_cluster_merger/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_cluster_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_cluster_merger/package.xml b/perception/autoware_cluster_merger/package.xml index e93243de2c8b9..29cbe8b5be016 100644 --- a/perception/autoware_cluster_merger/package.xml +++ b/perception/autoware_cluster_merger/package.xml @@ -2,7 +2,7 @@ autoware_cluster_merger - 0.38.0 + 0.39.0 The ROS 2 cluster merger package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_compare_map_segmentation/CHANGELOG.rst b/perception/autoware_compare_map_segmentation/CHANGELOG.rst index 70674495527e7..b45f1b3e64076 100644 --- a/perception/autoware_compare_map_segmentation/CHANGELOG.rst +++ b/perception/autoware_compare_map_segmentation/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_compare_map_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_compare_map_segmentation): fix cppcheck constVariableReference (`#9196 `_) +* Contributors: Esteve Fernandez, Ryuta Kambe, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_compare_map_segmentation/package.xml b/perception/autoware_compare_map_segmentation/package.xml index de3d97df91c6f..b25ca8bfd829d 100644 --- a/perception/autoware_compare_map_segmentation/package.xml +++ b/perception/autoware_compare_map_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_compare_map_segmentation - 0.38.0 + 0.39.0 The ROS 2 autoware_compare_map_segmentation package amc-nu Yukihiro Saito diff --git a/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst b/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst index fcff5c1964a10..e4a85d38559b0 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst +++ b/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_crosswalk_traffic_light_estimator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Masato Saeki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_crosswalk_traffic_light_estimator/package.xml b/perception/autoware_crosswalk_traffic_light_estimator/package.xml index abe5c65d3aa1d..12e689b5b50e3 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/package.xml +++ b/perception/autoware_crosswalk_traffic_light_estimator/package.xml @@ -1,7 +1,7 @@ autoware_crosswalk_traffic_light_estimator - 0.38.0 + 0.39.0 The autoware_crosswalk_traffic_light_estimator package Satoshi Ota diff --git a/perception/autoware_detected_object_feature_remover/CHANGELOG.rst b/perception/autoware_detected_object_feature_remover/CHANGELOG.rst index 1c956f5ae6469..2f887760e3970 100644 --- a/perception/autoware_detected_object_feature_remover/CHANGELOG.rst +++ b/perception/autoware_detected_object_feature_remover/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_detected_object_feature_remover ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_detected_object_feature_remover/package.xml b/perception/autoware_detected_object_feature_remover/package.xml index aa9eaa9c9df79..45f7d6e9036e7 100644 --- a/perception/autoware_detected_object_feature_remover/package.xml +++ b/perception/autoware_detected_object_feature_remover/package.xml @@ -2,7 +2,7 @@ autoware_detected_object_feature_remover - 0.38.0 + 0.39.0 The autoware_detected_object_feature_remover package Tomoya Kimura Yoshi Ri diff --git a/perception/autoware_detected_object_validation/CHANGELOG.rst b/perception/autoware_detected_object_validation/CHANGELOG.rst index ee2a4c502e33e..ebe5562fc2ec0 100644 --- a/perception/autoware_detected_object_validation/CHANGELOG.rst +++ b/perception/autoware_detected_object_validation/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_detected_object_validation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_detected_object_validation): fix bugprone-incorrect-roundings (`#9220 `_) + fix: bugprone-incorrect-roundings +* fix(autoware_detected_object_validation): fix clang-diagnostic-error (`#9215 `_) + fix: clang-c-error +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo, kobayu858 + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_detected_object_validation/package.xml b/perception/autoware_detected_object_validation/package.xml index 7c6f34e95a015..777fcea4db226 100644 --- a/perception/autoware_detected_object_validation/package.xml +++ b/perception/autoware_detected_object_validation/package.xml @@ -2,7 +2,7 @@ autoware_detected_object_validation - 0.38.0 + 0.39.0 The ROS 2 detected_object_validation package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_detection_by_tracker/CHANGELOG.rst b/perception/autoware_detection_by_tracker/CHANGELOG.rst index 0671601742afb..98d6dbe40f4a6 100644 --- a/perception/autoware_detection_by_tracker/CHANGELOG.rst +++ b/perception/autoware_detection_by_tracker/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_detection_by_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_detection_by_tracker/package.xml b/perception/autoware_detection_by_tracker/package.xml index 05f0ad9b4e109..cee180ba43c29 100644 --- a/perception/autoware_detection_by_tracker/package.xml +++ b/perception/autoware_detection_by_tracker/package.xml @@ -2,7 +2,7 @@ autoware_detection_by_tracker - 0.38.0 + 0.39.0 The ROS 2 autoware_detection_by_tracker package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_elevation_map_loader/CHANGELOG.rst b/perception/autoware_elevation_map_loader/CHANGELOG.rst index cbf29b22a46be..bd4d313348d9b 100644 --- a/perception/autoware_elevation_map_loader/CHANGELOG.rst +++ b/perception/autoware_elevation_map_loader/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_elevation_map_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_elevation_map_loader/package.xml b/perception/autoware_elevation_map_loader/package.xml index d80c8f3d67893..9a63c2fa569cc 100644 --- a/perception/autoware_elevation_map_loader/package.xml +++ b/perception/autoware_elevation_map_loader/package.xml @@ -2,7 +2,7 @@ autoware_elevation_map_loader - 0.38.0 + 0.39.0 The autoware_elevation_map_loader package Kosuke Takeuchi Taichi Higashide diff --git a/perception/autoware_euclidean_cluster/CHANGELOG.rst b/perception/autoware_euclidean_cluster/CHANGELOG.rst index b62e10d3c224f..9702b99a0b643 100644 --- a/perception/autoware_euclidean_cluster/CHANGELOG.rst +++ b/perception/autoware_euclidean_cluster/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_euclidean_cluster ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_euclidean_cluster): fix bugprone-misplaced-widening-cast (`#9227 `_) + fix: bugprone-misplaced-widening-cast +* Contributors: Esteve Fernandez, Yutaka Kondo, kobayu858 + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_euclidean_cluster/package.xml b/perception/autoware_euclidean_cluster/package.xml index 18de86fba7bcb..d740c35fbd94d 100644 --- a/perception/autoware_euclidean_cluster/package.xml +++ b/perception/autoware_euclidean_cluster/package.xml @@ -2,7 +2,7 @@ autoware_euclidean_cluster - 0.38.0 + 0.39.0 The autoware_euclidean_cluster package Yukihiro Saito Dai Nguyen diff --git a/perception/autoware_ground_segmentation/CHANGELOG.rst b/perception/autoware_ground_segmentation/CHANGELOG.rst index faa4e568eb906..7c2dbb7a2413c 100644 --- a/perception/autoware_ground_segmentation/CHANGELOG.rst +++ b/perception/autoware_ground_segmentation/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_ground_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_ground_segmentation/package.xml b/perception/autoware_ground_segmentation/package.xml index 1cd7df3be4aa1..3ac3047654a96 100644 --- a/perception/autoware_ground_segmentation/package.xml +++ b/perception/autoware_ground_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_ground_segmentation - 0.38.0 + 0.39.0 The ROS 2 autoware_ground_segmentation package amc-nu Yukihiro Saito diff --git a/perception/autoware_image_projection_based_fusion/CHANGELOG.rst b/perception/autoware_image_projection_based_fusion/CHANGELOG.rst index 4a309a3e4dcff..87d1bc0c2d687 100644 --- a/perception/autoware_image_projection_based_fusion/CHANGELOG.rst +++ b/perception/autoware_image_projection_based_fusion/CHANGELOG.rst @@ -2,6 +2,29 @@ Changelog for package autoware_image_projection_based_fusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_image_projection_based_fusion): make optional to consider lens distortion in the point projection (`#9233 `_) + chore: add point_project_to_unrectified_image parameter to fusion_common.param.yaml +* fix(autoware_image_projection_based_fusion): fix bugprone-misplaced-widening-cast (`#9226 `_) + * fix: bugprone-misplaced-widening-cast + * fix: clang-format + --------- +* fix(autoware_image_projection_based_fusion): fix bugprone-misplaced-widening-cast (`#9229 `_) + * fix: bugprone-misplaced-widening-cast + * fix: clang-format + --------- +* Contributors: Esteve Fernandez, Taekjin LEE, Yutaka Kondo, kobayu858 + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index 335c4712071e0..70aa2246d1cdf 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -2,7 +2,7 @@ autoware_image_projection_based_fusion - 0.38.0 + 0.39.0 The autoware_image_projection_based_fusion package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst b/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst index 08824ecfbd3aa..e55a52d6924d5 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst +++ b/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_lidar_apollo_instance_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_lidar_apollo_instance_segmentation): fix cppcheck suspiciousFloatingPointCast (`#9195 `_) +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Ryuta Kambe, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_lidar_apollo_instance_segmentation/package.xml b/perception/autoware_lidar_apollo_instance_segmentation/package.xml index b0f653dbeb3d0..dd48f1a2844d4 100755 --- a/perception/autoware_lidar_apollo_instance_segmentation/package.xml +++ b/perception/autoware_lidar_apollo_instance_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_lidar_apollo_instance_segmentation - 0.38.0 + 0.39.0 autoware_lidar_apollo_instance_segmentation Yoshi Ri Yukihiro Saito diff --git a/perception/autoware_lidar_centerpoint/CHANGELOG.rst b/perception/autoware_lidar_centerpoint/CHANGELOG.rst index 6809f690c75d1..b10fd533af90f 100644 --- a/perception/autoware_lidar_centerpoint/CHANGELOG.rst +++ b/perception/autoware_lidar_centerpoint/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_lidar_centerpoint ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_lidar_centerpoint/package.xml b/perception/autoware_lidar_centerpoint/package.xml index 4f33fd14dbb8f..9734e56a29d57 100644 --- a/perception/autoware_lidar_centerpoint/package.xml +++ b/perception/autoware_lidar_centerpoint/package.xml @@ -2,7 +2,7 @@ autoware_lidar_centerpoint - 0.38.0 + 0.39.0 The autoware_lidar_centerpoint package Kenzo Lobos-Tsunekawa Koji Minoda diff --git a/perception/autoware_lidar_transfusion/CHANGELOG.rst b/perception/autoware_lidar_transfusion/CHANGELOG.rst index bfde461fad192..94f49d65991c8 100644 --- a/perception/autoware_lidar_transfusion/CHANGELOG.rst +++ b/perception/autoware_lidar_transfusion/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_lidar_transfusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_lidar_transfusion/package.xml b/perception/autoware_lidar_transfusion/package.xml index 0714447a6c5c7..a4dd66c27db0e 100644 --- a/perception/autoware_lidar_transfusion/package.xml +++ b/perception/autoware_lidar_transfusion/package.xml @@ -2,7 +2,7 @@ autoware_lidar_transfusion - 0.38.0 + 0.39.0 The lidar_transfusion package Amadeusz Szymko Kenzo Lobos-Tsunekawa diff --git a/perception/autoware_map_based_prediction/CHANGELOG.rst b/perception/autoware_map_based_prediction/CHANGELOG.rst index 27297417c6563..69769df3aa04d 100644 --- a/perception/autoware_map_based_prediction/CHANGELOG.rst +++ b/perception/autoware_map_based_prediction/CHANGELOG.rst @@ -2,6 +2,36 @@ Changelog for package autoware_map_based_prediction ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(map_based_prediction): move member functions to utils (`#9225 `_) +* refactor(map_based_prediction): divide objectsCallback (`#9219 `_) +* refactor(autoware_map_based_prediction): split pedestrian and bicycle predictor (`#9201 `_) + * refactor: grouping functions + * refactor: grouping parameters + * refactor: rename member road_users_history to road_users_history\_ + * refactor: separate util functions + * refactor: Add predictor_vru.cpp and utils.cpp to map_based_prediction_node + * refactor: Add explicit template instantiation for removeOldObjectsHistory function + * refactor: Add tf2_geometry_msgs to data_structure + * refactor: Remove unused variables and functions in map_based_prediction_node.cpp + * Update perception/autoware_map_based_prediction/include/map_based_prediction/predictor_vru.hpp + * Apply suggestions from code review + * style(pre-commit): autofix + --------- + Co-authored-by: Mamoru Sobue + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Mamoru Sobue, Taekjin LEE, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_map_based_prediction/package.xml b/perception/autoware_map_based_prediction/package.xml index 161429d24ad2a..3d7cba491fe0e 100644 --- a/perception/autoware_map_based_prediction/package.xml +++ b/perception/autoware_map_based_prediction/package.xml @@ -2,7 +2,7 @@ autoware_map_based_prediction - 0.38.0 + 0.39.0 This package implements a map_based_prediction Tomoya Kimura Yoshi Ri diff --git a/perception/autoware_multi_object_tracker/CHANGELOG.rst b/perception/autoware_multi_object_tracker/CHANGELOG.rst index 593a9d70c4346..5f8ee4ef00869 100644 --- a/perception/autoware_multi_object_tracker/CHANGELOG.rst +++ b/perception/autoware_multi_object_tracker/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_multi_object_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_multi_object_tracker/package.xml b/perception/autoware_multi_object_tracker/package.xml index 5eb591d60133f..aa5c4968e36f9 100644 --- a/perception/autoware_multi_object_tracker/package.xml +++ b/perception/autoware_multi_object_tracker/package.xml @@ -2,7 +2,7 @@ autoware_multi_object_tracker - 0.38.0 + 0.39.0 The ROS 2 autoware_multi_object_tracker package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_merger/CHANGELOG.rst b/perception/autoware_object_merger/CHANGELOG.rst index e4af14846d835..2e1adbb4b8be6 100644 --- a/perception/autoware_object_merger/CHANGELOG.rst +++ b/perception/autoware_object_merger/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_object_merger/package.xml b/perception/autoware_object_merger/package.xml index 75af6239450c7..84a9ec64cf3f0 100644 --- a/perception/autoware_object_merger/package.xml +++ b/perception/autoware_object_merger/package.xml @@ -2,7 +2,7 @@ autoware_object_merger - 0.38.0 + 0.39.0 The autoware_object_merger package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_range_splitter/CHANGELOG.rst b/perception/autoware_object_range_splitter/CHANGELOG.rst index 6552fd133981c..b0f2a81744b8e 100644 --- a/perception/autoware_object_range_splitter/CHANGELOG.rst +++ b/perception/autoware_object_range_splitter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_object_range_splitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_object_range_splitter/package.xml b/perception/autoware_object_range_splitter/package.xml index d220d221bf8f4..27503850261d5 100644 --- a/perception/autoware_object_range_splitter/package.xml +++ b/perception/autoware_object_range_splitter/package.xml @@ -2,7 +2,7 @@ autoware_object_range_splitter - 0.38.0 + 0.39.0 The autoware_object_range_splitter package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_velocity_splitter/CHANGELOG.rst b/perception/autoware_object_velocity_splitter/CHANGELOG.rst index 66513afe678ca..9d38280224125 100644 --- a/perception/autoware_object_velocity_splitter/CHANGELOG.rst +++ b/perception/autoware_object_velocity_splitter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_object_velocity_splitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_object_velocity_splitter/package.xml b/perception/autoware_object_velocity_splitter/package.xml index 936bb40804882..48ffa93f05102 100644 --- a/perception/autoware_object_velocity_splitter/package.xml +++ b/perception/autoware_object_velocity_splitter/package.xml @@ -2,7 +2,7 @@ autoware_object_velocity_splitter - 0.38.0 + 0.39.0 autoware_object_velocity_splitter Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst b/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst index 8994678344025..e020be4cc906a 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst +++ b/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_occupancy_grid_map_outlier_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/package.xml b/perception/autoware_occupancy_grid_map_outlier_filter/package.xml index 1a5dc84c97e50..c8c1f15f72c0d 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/package.xml +++ b/perception/autoware_occupancy_grid_map_outlier_filter/package.xml @@ -2,7 +2,7 @@ autoware_occupancy_grid_map_outlier_filter - 0.38.0 + 0.39.0 The ROS 2 occupancy_grid_map_outlier_filter package amc-nu Yukihiro Saito diff --git a/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst b/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst index 2906f0f1f76a3..6668ef1c29ed9 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst +++ b/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_probabilistic_occupancy_grid_map ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_probabilistic_occupancy_grid_map): fix bugprone-incorrect-roundings (`#9221 `_) + fix: bugprone-incorrect-roundings +* Contributors: Esteve Fernandez, Yutaka Kondo, kobayu858 + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_probabilistic_occupancy_grid_map/package.xml b/perception/autoware_probabilistic_occupancy_grid_map/package.xml index 60f6cefcc6219..e5bd0eebb9b2e 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/package.xml +++ b/perception/autoware_probabilistic_occupancy_grid_map/package.xml @@ -2,7 +2,7 @@ autoware_probabilistic_occupancy_grid_map - 0.38.0 + 0.39.0 generate probabilistic occupancy grid map Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst b/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst index be3d4cb398b51..8eb064446cbba 100644 --- a/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst +++ b/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_crossing_objects_noise_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_radar_crossing_objects_noise_filter/package.xml b/perception/autoware_radar_crossing_objects_noise_filter/package.xml index f0bcfc6d30eee..5536033aa1319 100644 --- a/perception/autoware_radar_crossing_objects_noise_filter/package.xml +++ b/perception/autoware_radar_crossing_objects_noise_filter/package.xml @@ -2,7 +2,7 @@ autoware_radar_crossing_objects_noise_filter - 0.38.0 + 0.39.0 autoware_radar_crossing_objects_noise_filter Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst b/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst index e1c5497782ae0..9c4e7c527ecb7 100644 --- a/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst +++ b/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_fusion_to_detected_object ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_radar_fusion_to_detected_object/package.xml b/perception/autoware_radar_fusion_to_detected_object/package.xml index 07de2ac9532e9..82f2f0926e929 100644 --- a/perception/autoware_radar_fusion_to_detected_object/package.xml +++ b/perception/autoware_radar_fusion_to_detected_object/package.xml @@ -2,7 +2,7 @@ autoware_radar_fusion_to_detected_object - 0.38.0 + 0.39.0 autoware_radar_fusion_to_detected_object Satoshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_object_clustering/CHANGELOG.rst b/perception/autoware_radar_object_clustering/CHANGELOG.rst index e2a9c19b6f086..df38cbed59c27 100644 --- a/perception/autoware_radar_object_clustering/CHANGELOG.rst +++ b/perception/autoware_radar_object_clustering/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_object_clustering ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_radar_object_clustering/package.xml b/perception/autoware_radar_object_clustering/package.xml index fc103a531ee1d..a4611a68f93f2 100644 --- a/perception/autoware_radar_object_clustering/package.xml +++ b/perception/autoware_radar_object_clustering/package.xml @@ -2,7 +2,7 @@ autoware_radar_object_clustering - 0.38.0 + 0.39.0 autoware_radar_object_clustering Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_object_tracker/CHANGELOG.rst b/perception/autoware_radar_object_tracker/CHANGELOG.rst index f2490cc59c4fc..dde801b38e9aa 100644 --- a/perception/autoware_radar_object_tracker/CHANGELOG.rst +++ b/perception/autoware_radar_object_tracker/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_object_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_radar_object_tracker/package.xml b/perception/autoware_radar_object_tracker/package.xml index 3badf1ea766f1..f255ab28b14b9 100644 --- a/perception/autoware_radar_object_tracker/package.xml +++ b/perception/autoware_radar_object_tracker/package.xml @@ -2,7 +2,7 @@ autoware_radar_object_tracker - 0.38.0 + 0.39.0 Do tracking radar object Yoshi Ri Yukihiro Saito diff --git a/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst b/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst index 38e0a25549f76..3d880f603fdb6 100644 --- a/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst +++ b/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_tracks_msgs_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_radar_tracks_msgs_converter/package.xml b/perception/autoware_radar_tracks_msgs_converter/package.xml index 9efcd7a5e1c02..d84b7e8473f83 100644 --- a/perception/autoware_radar_tracks_msgs_converter/package.xml +++ b/perception/autoware_radar_tracks_msgs_converter/package.xml @@ -2,7 +2,7 @@ autoware_radar_tracks_msgs_converter - 0.38.0 + 0.39.0 autoware_radar_tracks_msgs_converter Satoshi Tanaka Shunsuke Miura diff --git a/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst b/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst index 1ed0d176125ab..1a20766e6a72c 100644 --- a/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst +++ b/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_raindrop_cluster_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_raindrop_cluster_filter/package.xml b/perception/autoware_raindrop_cluster_filter/package.xml index 859cad6e72886..08200191ad58b 100644 --- a/perception/autoware_raindrop_cluster_filter/package.xml +++ b/perception/autoware_raindrop_cluster_filter/package.xml @@ -2,7 +2,7 @@ autoware_raindrop_cluster_filter - 0.38.0 + 0.39.0 The ROS 2 filter cluster package Yukihiro Saito Dai Nguyen diff --git a/perception/autoware_shape_estimation/CHANGELOG.rst b/perception/autoware_shape_estimation/CHANGELOG.rst index 276854066ef08..19630554193ec 100644 --- a/perception/autoware_shape_estimation/CHANGELOG.rst +++ b/perception/autoware_shape_estimation/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_shape_estimation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_shape_estimation/package.xml b/perception/autoware_shape_estimation/package.xml index f2a1e0e48b5a7..a6a9910155120 100644 --- a/perception/autoware_shape_estimation/package.xml +++ b/perception/autoware_shape_estimation/package.xml @@ -2,7 +2,7 @@ autoware_shape_estimation - 0.38.0 + 0.39.0 This package implements a shape estimation algorithm as a ROS 2 node Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_simple_object_merger/CHANGELOG.rst b/perception/autoware_simple_object_merger/CHANGELOG.rst index f9b905a340f12..8c9ac43a8382f 100644 --- a/perception/autoware_simple_object_merger/CHANGELOG.rst +++ b/perception/autoware_simple_object_merger/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_simple_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_simple_object_merger/package.xml b/perception/autoware_simple_object_merger/package.xml index 594ba9959de29..b42544aede418 100644 --- a/perception/autoware_simple_object_merger/package.xml +++ b/perception/autoware_simple_object_merger/package.xml @@ -1,7 +1,7 @@ autoware_simple_object_merger - 0.38.0 + 0.39.0 autoware_simple_object_merger Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_tensorrt_classifier/CHANGELOG.rst b/perception/autoware_tensorrt_classifier/CHANGELOG.rst index ac517eba9c465..1fa80f20f6cb7 100644 --- a/perception/autoware_tensorrt_classifier/CHANGELOG.rst +++ b/perception/autoware_tensorrt_classifier/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_tensorrt_classifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_tensorrt_classifier/package.xml b/perception/autoware_tensorrt_classifier/package.xml index c628ba754eeaa..4813fe48cd4fd 100644 --- a/perception/autoware_tensorrt_classifier/package.xml +++ b/perception/autoware_tensorrt_classifier/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_classifier - 0.38.0 + 0.39.0 tensorrt classifier wrapper Dan Umeda diff --git a/perception/autoware_tensorrt_common/CHANGELOG.rst b/perception/autoware_tensorrt_common/CHANGELOG.rst index 9510da691fba7..48a26ad65a610 100644 --- a/perception/autoware_tensorrt_common/CHANGELOG.rst +++ b/perception/autoware_tensorrt_common/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_tensorrt_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_tensorrt_common/package.xml b/perception/autoware_tensorrt_common/package.xml index f2a03a4787cc8..7e29cf87b61c3 100644 --- a/perception/autoware_tensorrt_common/package.xml +++ b/perception/autoware_tensorrt_common/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_common - 0.38.0 + 0.39.0 tensorrt utility wrapper Taichi Higashide diff --git a/perception/autoware_tensorrt_yolox/CHANGELOG.rst b/perception/autoware_tensorrt_yolox/CHANGELOG.rst index e9cec23494914..b0883dab538d5 100644 --- a/perception/autoware_tensorrt_yolox/CHANGELOG.rst +++ b/perception/autoware_tensorrt_yolox/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_tensorrt_yolox ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_tensorrt_yolox/package.xml b/perception/autoware_tensorrt_yolox/package.xml index 294e13eb46d88..1c8cd51ee935c 100644 --- a/perception/autoware_tensorrt_yolox/package.xml +++ b/perception/autoware_tensorrt_yolox/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_yolox - 0.38.0 + 0.39.0 tensorrt library implementation for yolox Daisuke Nishimatsu diff --git a/perception/autoware_tracking_object_merger/CHANGELOG.rst b/perception/autoware_tracking_object_merger/CHANGELOG.rst index a4a65b6339ad1..0c6aad26b02d7 100644 --- a/perception/autoware_tracking_object_merger/CHANGELOG.rst +++ b/perception/autoware_tracking_object_merger/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_tracking_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_tracking_object_merger/package.xml b/perception/autoware_tracking_object_merger/package.xml index 89475edd247e6..fabe4132c96ed 100644 --- a/perception/autoware_tracking_object_merger/package.xml +++ b/perception/autoware_tracking_object_merger/package.xml @@ -2,7 +2,7 @@ autoware_tracking_object_merger - 0.38.0 + 0.39.0 merge tracking object Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_traffic_light_arbiter/CHANGELOG.rst b/perception/autoware_traffic_light_arbiter/CHANGELOG.rst index d1bc11f6e45f9..b60021ffb5503 100644 --- a/perception/autoware_traffic_light_arbiter/CHANGELOG.rst +++ b/perception/autoware_traffic_light_arbiter/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_traffic_light_arbiter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Masato Saeki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_traffic_light_arbiter/package.xml b/perception/autoware_traffic_light_arbiter/package.xml index 638bcbe941416..46500143ed951 100644 --- a/perception/autoware_traffic_light_arbiter/package.xml +++ b/perception/autoware_traffic_light_arbiter/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_arbiter - 0.38.0 + 0.39.0 The autoware_traffic_light_arbiter package Kenzo Lobos-Tsunekawa Shunsuke Miura diff --git a/perception/autoware_traffic_light_classifier/CHANGELOG.rst b/perception/autoware_traffic_light_classifier/CHANGELOG.rst index 7995044220180..394c8b3f7aeea 100644 --- a/perception/autoware_traffic_light_classifier/CHANGELOG.rst +++ b/perception/autoware_traffic_light_classifier/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package autoware_traffic_light_classifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Masato Saeki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_traffic_light_classifier/package.xml b/perception/autoware_traffic_light_classifier/package.xml index 99bdeb0643d91..5863de6ff50fd 100644 --- a/perception/autoware_traffic_light_classifier/package.xml +++ b/perception/autoware_traffic_light_classifier/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_classifier - 0.38.0 + 0.39.0 The autoware_traffic_light_classifier package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst b/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst index 87a5dda3c8add..8918f357e263b 100644 --- a/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst +++ b/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_traffic_light_fine_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Masato Saeki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_traffic_light_fine_detector/package.xml b/perception/autoware_traffic_light_fine_detector/package.xml index fd540d80e5d7e..a431f071f8150 100644 --- a/perception/autoware_traffic_light_fine_detector/package.xml +++ b/perception/autoware_traffic_light_fine_detector/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_fine_detector - 0.38.0 + 0.39.0 The autoware_traffic_light_fine_detector package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst b/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst index 5d05b6687cab3..312ef582da479 100644 --- a/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst +++ b/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_traffic_light_map_based_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Masato Saeki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_traffic_light_map_based_detector/package.xml b/perception/autoware_traffic_light_map_based_detector/package.xml index 0d0b1efe91d4c..6c22e091ee972 100644 --- a/perception/autoware_traffic_light_map_based_detector/package.xml +++ b/perception/autoware_traffic_light_map_based_detector/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_map_based_detector - 0.38.0 + 0.39.0 The autoware_traffic_light_map_based_detector package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst b/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst index 8842867c03485..4354885dcb143 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst +++ b/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_traffic_light_multi_camera_fusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Masato Saeki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_traffic_light_multi_camera_fusion/package.xml b/perception/autoware_traffic_light_multi_camera_fusion/package.xml index 111e34030c870..efa8571a660a8 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/package.xml +++ b/perception/autoware_traffic_light_multi_camera_fusion/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_multi_camera_fusion - 0.38.0 + 0.39.0 The autoware_traffic_light_multi_camera_fusion package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst b/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst index a378f3c04c1f3..fb31d9ffdf0c1 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst +++ b/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_traffic_light_occlusion_predictor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Masato Saeki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_traffic_light_occlusion_predictor/package.xml b/perception/autoware_traffic_light_occlusion_predictor/package.xml index bebe2ae189e74..b1dbc773b5eb0 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/package.xml +++ b/perception/autoware_traffic_light_occlusion_predictor/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_occlusion_predictor - 0.38.0 + 0.39.0 The autoware_traffic_light_occlusion_predictor package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_visualization/CHANGELOG.rst b/perception/autoware_traffic_light_visualization/CHANGELOG.rst index 2da3f57f659e5..7da332f0f878b 100644 --- a/perception/autoware_traffic_light_visualization/CHANGELOG.rst +++ b/perception/autoware_traffic_light_visualization/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_traffic_light_visualization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Masato Saeki, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/autoware_traffic_light_visualization/package.xml b/perception/autoware_traffic_light_visualization/package.xml index afe09b9461b18..210700799ea73 100644 --- a/perception/autoware_traffic_light_visualization/package.xml +++ b/perception/autoware_traffic_light_visualization/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_visualization - 0.38.0 + 0.39.0 The autoware_traffic_light_visualization package Yukihiro Saito Tao Zhong diff --git a/perception/perception_utils/CHANGELOG.rst b/perception/perception_utils/CHANGELOG.rst index fbe74bbf6d28a..2dbb57cbd2f48 100644 --- a/perception/perception_utils/CHANGELOG.rst +++ b/perception/perception_utils/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package perception_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/perception/perception_utils/package.xml b/perception/perception_utils/package.xml index d3d90a4d5ac26..7001d249e1f52 100644 --- a/perception/perception_utils/package.xml +++ b/perception/perception_utils/package.xml @@ -2,7 +2,7 @@ perception_utils - 0.38.0 + 0.39.0 The perception_utils package Shunsuke Miura Yoshi Ri diff --git a/planning/autoware_costmap_generator/CHANGELOG.rst b/planning/autoware_costmap_generator/CHANGELOG.rst index 58250e160fee9..2dad489bbc6a4 100644 --- a/planning/autoware_costmap_generator/CHANGELOG.rst +++ b/planning/autoware_costmap_generator/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_costmap_generator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(costmap_generator): use vehicle frame for lidar height thresholds (`#9311 `_) +* test(costmap_generator): unit test implementation for costmap generator (`#9149 `_) + * modify costmap generator directory structure + * rename class CostmapGenerator to CostmapGeneratorNode + * unit test for object_map_utils + * catch error from lookupTransform + * use polling subscriber in costmap generator node + * add test for costmap generator node + * add test for isActive() + * revert unnecessary changes + * remove commented out line + * minor fix + * Update planning/autoware_costmap_generator/src/costmap_generator.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Maxime CLEMENT, Yutaka Kondo, mkquda + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_costmap_generator/package.xml b/planning/autoware_costmap_generator/package.xml index 8779c1e706123..d3b03f171ef97 100644 --- a/planning/autoware_costmap_generator/package.xml +++ b/planning/autoware_costmap_generator/package.xml @@ -2,7 +2,7 @@ autoware_costmap_generator - 0.38.0 + 0.39.0 The autoware_costmap_generator package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst b/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst index d4e76a6d54d81..544a12e7cde26 100644 --- a/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst +++ b/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_external_velocity_limit_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_external_velocity_limit_selector/package.xml b/planning/autoware_external_velocity_limit_selector/package.xml index 252b195945deb..4779de30519a0 100644 --- a/planning/autoware_external_velocity_limit_selector/package.xml +++ b/planning/autoware_external_velocity_limit_selector/package.xml @@ -2,7 +2,7 @@ autoware_external_velocity_limit_selector - 0.38.0 + 0.39.0 The autoware_external_velocity_limit_selector ROS 2 package Satoshi Ota Shinnosuke Hirakawa diff --git a/planning/autoware_freespace_planner/CHANGELOG.rst b/planning/autoware_freespace_planner/CHANGELOG.rst index dd7f0ce0416ce..277d7f96d5d15 100644 --- a/planning/autoware_freespace_planner/CHANGELOG.rst +++ b/planning/autoware_freespace_planner/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_freespace_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_freespace_planner/package.xml b/planning/autoware_freespace_planner/package.xml index 7e8c2c5beca6c..84818e70f220a 100644 --- a/planning/autoware_freespace_planner/package.xml +++ b/planning/autoware_freespace_planner/package.xml @@ -2,7 +2,7 @@ autoware_freespace_planner - 0.38.0 + 0.39.0 The autoware_freespace_planner package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst b/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst index 7832350b16067..c032ebe44f723 100644 --- a/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst +++ b/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package autoware_freespace_planning_algorithms ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(/autoware_freespace_planning_algorithms): fix cppcheck unusedFunction (`#9274 `_) +* fix(autoware_freespace_planning_algorithms): fix bugprone-unused-raii (`#9230 `_) + fix: bugprone-unused-raii +* Contributors: Esteve Fernandez, Ryuta Kambe, Yutaka Kondo, kobayu858 + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_freespace_planning_algorithms/package.xml b/planning/autoware_freespace_planning_algorithms/package.xml index 219a738d50423..9a9b7ad0c586f 100644 --- a/planning/autoware_freespace_planning_algorithms/package.xml +++ b/planning/autoware_freespace_planning_algorithms/package.xml @@ -2,7 +2,7 @@ autoware_freespace_planning_algorithms - 0.38.0 + 0.39.0 The autoware_freespace_planning_algorithms package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_mission_planner/CHANGELOG.rst b/planning/autoware_mission_planner/CHANGELOG.rst index 5859bddced76b..bdab400dfa983 100644 --- a/planning/autoware_mission_planner/CHANGELOG.rst +++ b/planning/autoware_mission_planner/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_mission_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_mission_planner/package.xml b/planning/autoware_mission_planner/package.xml index 8d188e53fdef5..d249d2fb00021 100644 --- a/planning/autoware_mission_planner/package.xml +++ b/planning/autoware_mission_planner/package.xml @@ -2,7 +2,7 @@ autoware_mission_planner - 0.38.0 + 0.39.0 The autoware_mission_planner package Takagi, Isamu Kosuke Takeuchi diff --git a/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst b/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst index b70fabb1500db..891d36e2a3be5 100644 --- a/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst +++ b/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_objects_of_interest_marker_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_objects_of_interest_marker_interface/package.xml b/planning/autoware_objects_of_interest_marker_interface/package.xml index c9e0a672c0bfc..15f2adac6924d 100644 --- a/planning/autoware_objects_of_interest_marker_interface/package.xml +++ b/planning/autoware_objects_of_interest_marker_interface/package.xml @@ -1,7 +1,7 @@ autoware_objects_of_interest_marker_interface - 0.38.0 + 0.39.0 The autoware_objects_of_interest_marker_interface package Fumiya Watanabe diff --git a/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst b/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst index 65d4428bbcbb0..8b0192c171a29 100644 --- a/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst +++ b/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst @@ -2,6 +2,45 @@ Changelog for package autoware_obstacle_cruise_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* chore(obstacle_cruise_planner): add function tests for a utils function (`#9206 `_) + * add utils test + --------- +* Contributors: Esteve Fernandez, Kem (TiankuiXian), Yuki TAKAGI, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index d8bf161ef866f..df760ee59de37 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -1,7 +1,7 @@ autoware_obstacle_cruise_planner - 0.38.0 + 0.39.0 The autoware_obstacle_cruise_planner package Takayuki Murooka diff --git a/planning/autoware_obstacle_stop_planner/CHANGELOG.rst b/planning/autoware_obstacle_stop_planner/CHANGELOG.rst index cffc56e34f282..2afc9c79edac5 100644 --- a/planning/autoware_obstacle_stop_planner/CHANGELOG.rst +++ b/planning/autoware_obstacle_stop_planner/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_obstacle_stop_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_obstacle_stop_planner/package.xml b/planning/autoware_obstacle_stop_planner/package.xml index 90c4b3230d5fc..d46ad5c6c2a0d 100644 --- a/planning/autoware_obstacle_stop_planner/package.xml +++ b/planning/autoware_obstacle_stop_planner/package.xml @@ -2,7 +2,7 @@ autoware_obstacle_stop_planner - 0.38.0 + 0.39.0 The autoware_obstacle_stop_planner package Satoshi Ota diff --git a/planning/autoware_path_optimizer/CHANGELOG.rst b/planning/autoware_path_optimizer/CHANGELOG.rst index 17d9495050dbe..07ea508e53c07 100644 --- a/planning/autoware_path_optimizer/CHANGELOG.rst +++ b/planning/autoware_path_optimizer/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_path_optimizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml index 7c5b1e68e759a..8ab7d50ccada4 100644 --- a/planning/autoware_path_optimizer/package.xml +++ b/planning/autoware_path_optimizer/package.xml @@ -2,7 +2,7 @@ autoware_path_optimizer - 0.38.0 + 0.39.0 The autoware_path_optimizer package Takayuki Murooka Kosuke Takeuchi diff --git a/planning/autoware_path_smoother/CHANGELOG.rst b/planning/autoware_path_smoother/CHANGELOG.rst index ab5e23100f6cd..823219e9dd303 100644 --- a/planning/autoware_path_smoother/CHANGELOG.rst +++ b/planning/autoware_path_smoother/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_path_smoother ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_path_smoother/package.xml b/planning/autoware_path_smoother/package.xml index 6c8b3efec678b..572cf514b7be5 100644 --- a/planning/autoware_path_smoother/package.xml +++ b/planning/autoware_path_smoother/package.xml @@ -2,7 +2,7 @@ autoware_path_smoother - 0.38.0 + 0.39.0 The autoware_path_smoother package Takayuki Murooka Maxime CLEMENT diff --git a/planning/autoware_planning_test_manager/CHANGELOG.rst b/planning/autoware_planning_test_manager/CHANGELOG.rst index 67cf805f36426..3d674c64296af 100644 --- a/planning/autoware_planning_test_manager/CHANGELOG.rst +++ b/planning/autoware_planning_test_manager/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_planning_test_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index 0ce898cb3fbf9..ec22d871013d3 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -2,7 +2,7 @@ autoware_planning_test_manager - 0.38.0 + 0.39.0 ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara Takamasa Horibe diff --git a/planning/autoware_planning_topic_converter/CHANGELOG.rst b/planning/autoware_planning_topic_converter/CHANGELOG.rst index 7152b275dd5d9..897a99d1e0bc2 100644 --- a/planning/autoware_planning_topic_converter/CHANGELOG.rst +++ b/planning/autoware_planning_topic_converter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_planning_topic_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_planning_topic_converter/package.xml b/planning/autoware_planning_topic_converter/package.xml index 42ce0fdc16588..3503a9bebda40 100644 --- a/planning/autoware_planning_topic_converter/package.xml +++ b/planning/autoware_planning_topic_converter/package.xml @@ -1,7 +1,7 @@ autoware_planning_topic_converter - 0.38.0 + 0.39.0 The autoware_planning_topic_converter package Satoshi OTA diff --git a/planning/autoware_planning_validator/CHANGELOG.rst b/planning/autoware_planning_validator/CHANGELOG.rst index 7a8380f24cb8d..9828da69cf80d 100644 --- a/planning/autoware_planning_validator/CHANGELOG.rst +++ b/planning/autoware_planning_validator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_planning_validator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_planning_validator/package.xml b/planning/autoware_planning_validator/package.xml index 358d721b2f6e5..9db00b580b60d 100644 --- a/planning/autoware_planning_validator/package.xml +++ b/planning/autoware_planning_validator/package.xml @@ -2,7 +2,7 @@ autoware_planning_validator - 0.38.0 + 0.39.0 ros node for autoware_planning_validator Takamasa Horibe Kosuke Takeuchi diff --git a/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst b/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst index 245fa0b4ef084..7a8d11d37fe1e 100644 --- a/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst +++ b/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_remaining_distance_time_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml index 852139fb7f7b3..55033af92656b 100644 --- a/planning/autoware_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -1,7 +1,7 @@ autoware_remaining_distance_time_calculator - 0.38.0 + 0.39.0 Calculates and publishes remaining distance and time of the mission. Ahmed Ebrahim diff --git a/planning/autoware_route_handler/CHANGELOG.rst b/planning/autoware_route_handler/CHANGELOG.rst index 9b5b4a5efd159..37c1db12186ce 100644 --- a/planning/autoware_route_handler/CHANGELOG.rst +++ b/planning/autoware_route_handler/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_route_handler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_route_handler/package.xml b/planning/autoware_route_handler/package.xml index 1ad0529f971c5..78a024a8c5f82 100644 --- a/planning/autoware_route_handler/package.xml +++ b/planning/autoware_route_handler/package.xml @@ -2,7 +2,7 @@ autoware_route_handler - 0.38.0 + 0.39.0 The route_handling package Fumiya Watanabe Zulfaqar Azmi diff --git a/planning/autoware_rtc_interface/CHANGELOG.rst b/planning/autoware_rtc_interface/CHANGELOG.rst index 71224eefc2747..3c6fe2604d2ab 100644 --- a/planning/autoware_rtc_interface/CHANGELOG.rst +++ b/planning/autoware_rtc_interface/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_rtc_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_rtc_interface): fix dependency (`#9237 `_) +* fix(rtc_interface): update requested field for every cooperateStatus state (`#9211 `_) + * fix rtc_interface + * fix test condition + --------- +* feat(rtc_interface): add requested field (`#9202 `_) + * add requested feature + * Update planning/autoware_rtc_interface/test/test_rtc_interface.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> +* Contributors: Esteve Fernandez, Go Sakayori, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_rtc_interface/package.xml b/planning/autoware_rtc_interface/package.xml index 3479ae18825e9..668e31093072e 100644 --- a/planning/autoware_rtc_interface/package.xml +++ b/planning/autoware_rtc_interface/package.xml @@ -1,7 +1,7 @@ autoware_rtc_interface - 0.38.0 + 0.39.0 The autoware_rtc_interface package Fumiya Watanabe diff --git a/planning/autoware_scenario_selector/CHANGELOG.rst b/planning/autoware_scenario_selector/CHANGELOG.rst index 642e823ea9236..0e1a560fa95e8 100644 --- a/planning/autoware_scenario_selector/CHANGELOG.rst +++ b/planning/autoware_scenario_selector/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_scenario_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_scenario_selector/package.xml b/planning/autoware_scenario_selector/package.xml index 6579427273df5..9787f95ed9fde 100644 --- a/planning/autoware_scenario_selector/package.xml +++ b/planning/autoware_scenario_selector/package.xml @@ -2,7 +2,7 @@ autoware_scenario_selector - 0.38.0 + 0.39.0 The autoware_scenario_selector ROS 2 package Taiki Tanaka Tomoya Kimura diff --git a/planning/autoware_static_centerline_generator/CHANGELOG.rst b/planning/autoware_static_centerline_generator/CHANGELOG.rst index efb482f3f33e1..6fac2e4677528 100644 --- a/planning/autoware_static_centerline_generator/CHANGELOG.rst +++ b/planning/autoware_static_centerline_generator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_static_centerline_generator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index b9b1267a343db..a6d97d6fae2f7 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -2,7 +2,7 @@ autoware_static_centerline_generator - 0.38.0 + 0.39.0 The autoware_static_centerline_generator package Takayuki Murooka Kosuke Takeuchi diff --git a/planning/autoware_surround_obstacle_checker/CHANGELOG.rst b/planning/autoware_surround_obstacle_checker/CHANGELOG.rst index 5a9105c869042..077b52e08e342 100644 --- a/planning/autoware_surround_obstacle_checker/CHANGELOG.rst +++ b/planning/autoware_surround_obstacle_checker/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_surround_obstacle_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_surround_obstacle_checker/package.xml b/planning/autoware_surround_obstacle_checker/package.xml index e8c1ca6e9eb34..64a626c0ccb60 100644 --- a/planning/autoware_surround_obstacle_checker/package.xml +++ b/planning/autoware_surround_obstacle_checker/package.xml @@ -2,7 +2,7 @@ autoware_surround_obstacle_checker - 0.38.0 + 0.39.0 The autoware_surround_obstacle_checker package Satoshi Ota Go Sakayori diff --git a/planning/autoware_velocity_smoother/CHANGELOG.rst b/planning/autoware_velocity_smoother/CHANGELOG.rst index 33aa32d835398..14c905b82cfa1 100644 --- a/planning/autoware_velocity_smoother/CHANGELOG.rst +++ b/planning/autoware_velocity_smoother/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_velocity_smoother ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/autoware_velocity_smoother/package.xml b/planning/autoware_velocity_smoother/package.xml index e0e028656e8be..c27a984c36681 100644 --- a/planning/autoware_velocity_smoother/package.xml +++ b/planning/autoware_velocity_smoother/package.xml @@ -2,7 +2,7 @@ autoware_velocity_smoother - 0.38.0 + 0.39.0 The autoware_velocity_smoother package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst index aa4bfb81d81db..e736da5b9fb49 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_path_avoidance_by_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml index 77ebb1e160644..43195e8ca502b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_avoidance_by_lane_change_module - 0.38.0 + 0.39.0 The behavior_path_avoidance_by_lane_change_module package Satoshi Ota diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst index 9f25d197cc113..7219f13994710 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_path_dynamic_obstacle_avoidance_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml index 7849278a16f1a..1829d9a949115 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_dynamic_obstacle_avoidance_module - 0.38.0 + 0.39.0 The autoware_behavior_path_dynamic_obstacle_avoidance_module package Takayuki Murooka diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst index 501e950312718..cdd6bc1033d7e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_path_external_request_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml index c09f34bf53574..981f119357ca0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_external_request_lane_change_module - 0.38.0 + 0.39.0 The autoware_behavior_path_external_request_lane_change_module package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst index 3617b609cc31c..1813e0ac901f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_behavior_path_goal_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(goal_planner): remove reference_goal_pose getter/setter (`#9270 `_) +* feat(goal_planner): safety check with only parking path (`#9293 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(goal_planner): sort candidate path only when num to avoid is different (`#9271 `_) +* fix(autoware_behavior_path_goal_planner_module): fix cppcheck unreadVariable (`#9192 `_) +* Contributors: Esteve Fernandez, Kosuke Takeuchi, Mamoru Sobue, Ryuta Kambe, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml index 30d3c96aa6c87..dc7221d0fd604 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_goal_planner_module - 0.38.0 + 0.39.0 The autoware_behavior_path_goal_planner_module package Kosuke Takeuchi diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst index cc4ff795e150a..572a09aeda817 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst @@ -2,6 +2,45 @@ Changelog for package autoware_behavior_path_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(lane_change): remove std::optional from lanes polygon (`#9288 `_) +* fix(lane_change): extending lane change path for multiple lane change (RT1-8427) (`#9268 `_) + * RT1-8427 extending lc path for multiple lc + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(lane_change): correct computation of maximum lane changing length threshold (`#9279 `_) + fix computation of maximum lane changing length threshold +* refactor(lane_change): revert "remove std::optional from lanes polygon" (`#9272 `_) + Revert "refactor(lane_change): remove std::optional from lanes polygon (`#9267 `_)" + This reverts commit 0c70ea8793985c6aae90f851eeffdd2561fe04b3. +* refactor(lane_change): remove std::optional from lanes polygon (`#9267 `_) +* fix(lane_change): enable cancel when ego in turn direction lane (`#9124 `_) + * RT0-33893 add checks from prev intersection + * fix shadow variable + * fix logic + * update readme + * refactor get_ego_footprint + --------- +* test(bpp_common): add unit test for safety check (`#9223 `_) + * add test for object collision + * add test for more functions + * add docstring + * fix lane change + --------- +* Contributors: Esteve Fernandez, Go Sakayori, Yutaka Kondo, Zulfaqar Azmi, mkquda + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 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 aef3d357c20da..d4108003a9afe 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 @@ -2,7 +2,7 @@ autoware_behavior_path_lane_change_module - 0.38.0 + 0.39.0 The autoware_behavior_path_lane_change_module package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst index eb9dc2c942d71..ea088d6130c85 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_path_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml index 4cbb6b7ffb1cb..7fa591bd4a740 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_planner - 0.38.0 + 0.39.0 The behavior_path_planner package diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst index cba7021dcc6bc..0e0b6aa328d26 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst @@ -2,6 +2,41 @@ Changelog for package autoware_behavior_path_planner_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(goal_planner): safety check with only parking path (`#9293 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(behavior_path_planner_common): use boost intersects instead of overlaps (`#9289 `_) + * fix(behavior_path_planner_common): use boost intersects instead of overlaps + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp + Co-authored-by: Go Sakayori + --------- + Co-authored-by: Go Sakayori +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(bpp): prevent accessing nullopt (`#9269 `_) +* test(behavior_path_planner_common): add unit test for path shifter (`#9239 `_) + * add unit test for path shifter + * fix unnecessary modification + * fix spelling mistake + * add docstring + --------- +* test(bpp_common): add unit test for safety check (`#9223 `_) + * add test for object collision + * add test for more functions + * add docstring + * fix lane change + --------- +* fix(bpp): prevent accessing nullopt (`#9204 `_) + fix(bpp): calcDistanceToRedTrafficLight null +* Contributors: Esteve Fernandez, Go Sakayori, Kosuke Takeuchi, Shumpei Wakabayashi, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml index bd32cf42293a7..40506ad74a274 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_planner_common - 0.38.0 + 0.39.0 The autoware_behavior_path_planner_common package diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst index 7ca3438da02d0..e823e6501df47 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_behavior_path_sampling_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_behavior_path_sampling_planner_module): fix cppcheck unusedVariable (`#9190 `_) +* Contributors: Esteve Fernandez, Ryuta Kambe, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml index 8d33d41ee96a0..cd609a9dee40f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_sampling_planner_module - 0.38.0 + 0.39.0 The autoware_behavior_path_sampling_planner_module package Daniel Sanchez diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst index b1fd2c45965bc..58ab621b9c925 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_path_side_shift_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml index 05cb8be401554..6eac60c2411fd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_side_shift_module - 0.38.0 + 0.39.0 The autoware_behavior_path_side_shift_module package Satoshi Ota diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst index d4e3a843a8319..cbf67c171ee03 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package autoware_behavior_path_start_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(start_planner, lane_departure_checker): speed up by updating polygons (`#9309 `_) + speed up by updating polygons +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_behavior_path_start_planner_module): fix cppcheck unreadVariable (`#9277 `_) +* Contributors: Esteve Fernandez, Ryuta Kambe, Yutaka Kondo, danielsanchezaran + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml index 1d883477524b5..97f1a8569b132 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_start_planner_module - 0.38.0 + 0.39.0 The autoware_behavior_path_start_planner_module package Kosuke Takeuchi diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst index f6e5ba7526780..5d2af19f9ce2e 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst @@ -2,6 +2,31 @@ Changelog for package autoware_behavior_path_static_obstacle_avoidance_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* test(bpp_common): add unit test for safety check (`#9223 `_) + * add test for object collision + * add test for more functions + * add docstring + * fix lane change + --------- +* feat(static_obstacle_avoidance): operator request for ambiguous vehicle (`#9205 `_) + * add operator request feature + * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> +* Contributors: Esteve Fernandez, Go Sakayori, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml index ca7a2dab1191c..00f0db2224d5b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_static_obstacle_avoidance_module - 0.38.0 + 0.39.0 The autoware_behavior_path_static_obstacle_avoidance_module package Takamasa Horibe diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst index cca3b919daf18..6c312d3f90cb8 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_blind_spot_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml index b484c6a66cbac..1dd334f89c67f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_blind_spot_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_blind_spot_module package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst index f9fe6b4479c0a..8663879cc095f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_behavior_velocity_crosswalk_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback (`#9234 `_) +* test(crosswalk): add unit test (`#9228 `_) +* Contributors: Esteve Fernandez, Satoshi OTA, Yuki TAKAGI, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml index e6a0d93575f80..891a77e100435 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_crosswalk_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_crosswalk_module package Satoshi Ota diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst index 2db48d466139c..f53d95a981950 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_behavior_velocity_detection_area_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(detection_area)!: add retruction feature (`#9255 `_) +* Contributors: Esteve Fernandez, Yuki TAKAGI, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml index 14a1723f3be2a..1bd4e05af8447 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_detection_area_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_detection_area_module package Kyoichi Sugahara diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst index d7e0b2d2fd5ae..4bd9f8487b644 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst @@ -2,6 +2,25 @@ Changelog for package autoware_behavior_velocity_intersection_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(bvp): remove expired module safely (`#9212 `_) + * fix(bvp): remove expired module safely + * fix: remove module id set + * fix: use itr to erase expired module + * fix: remove unused function + --------- +* Contributors: Esteve Fernandez, Satoshi OTA, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml index f80aed04512cc..16c7a13f21320 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_intersection_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_intersection_module package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst index 6befa38af63e1..0d3e17d146747 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_no_drivable_lane_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml index f4e71d5bff78e..524aeec6d6c6d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_no_drivable_lane_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_no_drivable_lane_module package Ahmed Ebrahim diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst index 130aa5c56cd48..de6f32656fe5b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_behavior_velocity_no_stopping_area_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_behavior_velocity_no_stopping_area_module): fix cppcheck knownConditionTrueFalse (`#9189 `_) +* Contributors: Esteve Fernandez, Ryuta Kambe, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml index bc119becdfece..0873e3cd433d2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_no_stopping_area_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_no_stopping_area_module package Kosuke Takeuchi diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst index 42636a0ca1d89..695f4a63e3ae0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_occlusion_spot_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml index 34597b1c41a5f..9ce05294f86ed 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_occlusion_spot_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_occlusion_spot_module package Taiki Tanaka diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst index c4594d8bc0df4..eedb174bcd2c4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_behavior_velocity_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(bvp): use polling subscriber (`#9242 `_) + * fix(bvp): use polling subscriber + * fix: use newest policy + --------- +* Contributors: Esteve Fernandez, Satoshi OTA, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index 4dc4876010555..a7a892e521826 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_planner - 0.38.0 + 0.39.0 The autoware_behavior_velocity_planner package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst index de8e6e910e7a6..c702d7b763653 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst @@ -2,6 +2,25 @@ Changelog for package autoware_behavior_velocity_planner_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(bvp): remove expired module safely (`#9212 `_) + * fix(bvp): remove expired module safely + * fix: remove module id set + * fix: use itr to erase expired module + * fix: remove unused function + --------- +* Contributors: Esteve Fernandez, Satoshi OTA, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index 105b0528940bf..1e309ebd1caee 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_planner_common - 0.38.0 + 0.39.0 The autoware_behavior_velocity_planner_common package Tomoya Kimura diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst index 6ffbc52ff3077..ae2df69a585c0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_run_out_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml index 6aaab5817aad6..a5374f0e37bde 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_run_out_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_run_out_module package Tomohito Ando diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst index dda59c346fd20..d21af6839aaab 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_speed_bump_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml index 3018be3e328b8..6560a51b3a026 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_speed_bump_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_speed_bump_module package Tomoya Kimura diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst index 4bfe8d3d74a06..0fa84098defb2 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_stop_line_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml index c5e3690dd620d..7489e03c6ead0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_stop_line_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_stop_line_module package Yukinari Hisaki diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst index 361738a56b5b4..a1a2e65e5d749 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_template_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml index d0c43166cd670..2cae84e19929f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_template_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_template_module package Daniel Sanchez diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst index 80f08e3aec044..1ae51ad5bf695 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_traffic_light_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml index 244d03553351b..0ded242b6a3cf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_traffic_light_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_traffic_light_module package Satoshi Ota diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst index f811d901e6489..c0b26562f584c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_virtual_traffic_light_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml index b1ecfdb26bcde..581d03e71c06d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_virtual_traffic_light_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_virtual_traffic_light_module package Kosuke Takeuchi diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst index 1d9d0a1dbc9da..69ea69091532b 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_behavior_velocity_walkway_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml index 03724767271fe..9c706e3e13cd0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_walkway_module - 0.38.0 + 0.39.0 The autoware_behavior_velocity_walkway_module package Satoshi Ota diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst index 18a98316008ce..e05c363a76192 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_motion_velocity_dynamic_obstacle_stop_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml index 5916d20f5c42e..e66fb82704c05 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_dynamic_obstacle_stop_module - 0.38.0 + 0.39.0 dynamic_obstacle_stop module to stop ego when in the immediate path of a dynamic object Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst index 8519142e059eb..844d4425a6afd 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_motion_velocity_obstacle_velocity_limiter_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml index cd9dd1b756b64..268f331f86423 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml @@ -1,7 +1,7 @@ autoware_motion_velocity_obstacle_velocity_limiter_module - 0.38.0 + 0.39.0 Package to adjust velocities of a trajectory in order for the ride to feel safe Maxime CLEMENT diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst index 35ad88f5955db..57a3918601976 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_motion_velocity_out_of_lane_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(out_of_lane): correct calculations of the stop pose (`#9209 `_) +* Contributors: Esteve Fernandez, Maxime CLEMENT, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml index 18e072191905e..4001136b72ec0 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_out_of_lane_module - 0.38.0 + 0.39.0 The motion_velocity_out_of_lane_module package Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst index 2de2517dbf0e5..3b353111d1055 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_motion_velocity_planner_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml index 9f518044b9d05..650b3308d508b 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_planner_common - 0.38.0 + 0.39.0 Common functions and interfaces for motion_velocity_planner modules Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst index aabf62dffd79d..01fb10df7bd64 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package autoware_motion_velocity_planner_node ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Kem (TiankuiXian), Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml index 3e68d8262aae9..a28a24d4dae49 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_planner_node - 0.38.0 + 0.39.0 Node of the motion_velocity_planner Maxime Clement diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst b/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst index 3b3d46ee59b79..b3ab3bb13aa3c 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_bezier_sampler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/package.xml b/planning/sampling_based_planner/autoware_bezier_sampler/package.xml index 5293a01de4577..9da456248f0ce 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_bezier_sampler/package.xml @@ -1,7 +1,7 @@ autoware_bezier_sampler - 0.38.0 + 0.39.0 Package to sample trajectories using Bézier curves Maxime CLEMENT Maxime CLEMENT diff --git a/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst b/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst index 9d539fa198df1..e0123b1de0bd7 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_frenet_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/sampling_based_planner/autoware_frenet_planner/package.xml b/planning/sampling_based_planner/autoware_frenet_planner/package.xml index 8a6d4d487580d..11608baabeb76 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/package.xml +++ b/planning/sampling_based_planner/autoware_frenet_planner/package.xml @@ -1,7 +1,7 @@ autoware_frenet_planner - 0.38.0 + 0.39.0 The autoware_frenet_planner package for trajectory generation in Frenet frame Maxime CLEMENT Maxime CLEMENT diff --git a/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst b/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst index 6ad80c1f48ae0..33fb5a66d1ed6 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_path_sampler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/sampling_based_planner/autoware_path_sampler/package.xml b/planning/sampling_based_planner/autoware_path_sampler/package.xml index c4dafda08a14c..8f27509d27f67 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_path_sampler/package.xml @@ -2,7 +2,7 @@ autoware_path_sampler - 0.38.0 + 0.39.0 Package for the sampling-based path planner Maxime CLEMENT Apache License 2.0 diff --git a/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst b/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst index c571077d5d029..d07a47c0c4629 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_sampler_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/planning/sampling_based_planner/autoware_sampler_common/package.xml b/planning/sampling_based_planner/autoware_sampler_common/package.xml index d110807877761..b5b4ab3bd9dc8 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/package.xml +++ b/planning/sampling_based_planner/autoware_sampler_common/package.xml @@ -1,7 +1,7 @@ autoware_sampler_common - 0.38.0 + 0.39.0 Common classes and functions for sampling based planners Maxime CLEMENT Maxime CLEMENT diff --git a/sensing/autoware_cuda_utils/CHANGELOG.rst b/sensing/autoware_cuda_utils/CHANGELOG.rst index fe3b28768acbb..64b78ebc94eee 100644 --- a/sensing/autoware_cuda_utils/CHANGELOG.rst +++ b/sensing/autoware_cuda_utils/CHANGELOG.rst @@ -1,6 +1,19 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package autoware_cuda_utils -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo 0.38.0 (2024-11-08) ------------------- diff --git a/sensing/autoware_cuda_utils/package.xml b/sensing/autoware_cuda_utils/package.xml index ea65eda9a11f5..817aa395092aa 100644 --- a/sensing/autoware_cuda_utils/package.xml +++ b/sensing/autoware_cuda_utils/package.xml @@ -1,7 +1,7 @@ autoware_cuda_utils - 0.38.0 + 0.39.0 cuda utility library Daisuke Nishimatsu diff --git a/sensing/autoware_gnss_poser/CHANGELOG.rst b/sensing/autoware_gnss_poser/CHANGELOG.rst index 551ed898b5663..25713471aacbd 100644 --- a/sensing/autoware_gnss_poser/CHANGELOG.rst +++ b/sensing/autoware_gnss_poser/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package autoware_gnss_poser ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_gnss_poser/package.xml b/sensing/autoware_gnss_poser/package.xml index defcff66a1518..8304229b18a05 100644 --- a/sensing/autoware_gnss_poser/package.xml +++ b/sensing/autoware_gnss_poser/package.xml @@ -2,7 +2,7 @@ autoware_gnss_poser - 0.38.0 + 0.39.0 The ROS 2 autoware_gnss_poser package Yamato Ando Masahiro Sakamoto diff --git a/sensing/autoware_image_diagnostics/CHANGELOG.rst b/sensing/autoware_image_diagnostics/CHANGELOG.rst index cc0f34ff1a90b..db6df3ceedc67 100644 --- a/sensing/autoware_image_diagnostics/CHANGELOG.rst +++ b/sensing/autoware_image_diagnostics/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_image_diagnostics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_image_diagnostics/package.xml b/sensing/autoware_image_diagnostics/package.xml index cbf2579081b99..48109cfd22e91 100644 --- a/sensing/autoware_image_diagnostics/package.xml +++ b/sensing/autoware_image_diagnostics/package.xml @@ -2,7 +2,7 @@ autoware_image_diagnostics - 0.38.0 + 0.39.0 The autoware_image_diagnostics package Dai Nguyen Yoshi Ri diff --git a/sensing/autoware_image_transport_decompressor/CHANGELOG.rst b/sensing/autoware_image_transport_decompressor/CHANGELOG.rst index faf96ac052e25..fb82afbff8fe9 100644 --- a/sensing/autoware_image_transport_decompressor/CHANGELOG.rst +++ b/sensing/autoware_image_transport_decompressor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_image_transport_decompressor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_image_transport_decompressor/package.xml b/sensing/autoware_image_transport_decompressor/package.xml index 00de3283895c8..22766b6582631 100644 --- a/sensing/autoware_image_transport_decompressor/package.xml +++ b/sensing/autoware_image_transport_decompressor/package.xml @@ -2,7 +2,7 @@ autoware_image_transport_decompressor - 0.38.0 + 0.39.0 The image_transport_decompressor package Yukihiro Saito Kenzo Lobos-Tsunekawa diff --git a/sensing/autoware_imu_corrector/CHANGELOG.rst b/sensing/autoware_imu_corrector/CHANGELOG.rst index 3ee386a1481f3..926cd3a195e0f 100644 --- a/sensing/autoware_imu_corrector/CHANGELOG.rst +++ b/sensing/autoware_imu_corrector/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_imu_corrector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_imu_corrector/package.xml b/sensing/autoware_imu_corrector/package.xml index 2b33890d4dbd8..e32814af99863 100644 --- a/sensing/autoware_imu_corrector/package.xml +++ b/sensing/autoware_imu_corrector/package.xml @@ -2,7 +2,7 @@ autoware_imu_corrector - 0.38.0 + 0.39.0 The ROS 2 autoware_imu_corrector package Yamato Ando Taiki Yamada diff --git a/sensing/autoware_pcl_extensions/CHANGELOG.rst b/sensing/autoware_pcl_extensions/CHANGELOG.rst index 7d0c642b6ff8b..ef8cc108086b5 100644 --- a/sensing/autoware_pcl_extensions/CHANGELOG.rst +++ b/sensing/autoware_pcl_extensions/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_pcl_extensions ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_pcl_extensions/package.xml b/sensing/autoware_pcl_extensions/package.xml index 4601a043980b1..a141ebb31223f 100644 --- a/sensing/autoware_pcl_extensions/package.xml +++ b/sensing/autoware_pcl_extensions/package.xml @@ -2,7 +2,7 @@ autoware_pcl_extensions - 0.38.0 + 0.39.0 The autoware_pcl_extensions package Ryu Yamamoto Kenzo Lobos Tsunekawa diff --git a/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst b/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst index 126b444134bc8..6812ad076e60f 100644 --- a/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst +++ b/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst @@ -2,6 +2,27 @@ Changelog for package autoware_pointcloud_preprocessor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_pointcloud_preprocessor): fix the wrong naming of crop box parameter file (`#9258 `_) + fix: fix the wrong file name +* fix(autoware_pointcloud_preprocessor): launch file load parameter from yaml (`#8129 `_) + * feat: fix launch file + * chore: fix spell error + * chore: fix parameters file name + * chore: remove filter base + --------- +* Contributors: Esteve Fernandez, Yi-Hsiang Fang (Vivid), Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_pointcloud_preprocessor/package.xml b/sensing/autoware_pointcloud_preprocessor/package.xml index 85e42b4291626..20643d66d364c 100644 --- a/sensing/autoware_pointcloud_preprocessor/package.xml +++ b/sensing/autoware_pointcloud_preprocessor/package.xml @@ -2,7 +2,7 @@ autoware_pointcloud_preprocessor - 0.38.0 + 0.39.0 The ROS 2 autoware_pointcloud_preprocessor package amc-nu Yukihiro Saito diff --git a/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst b/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst index b9fe1abe13093..8524887c25bff 100644 --- a/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst +++ b/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_scan_to_pointcloud2 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_radar_scan_to_pointcloud2/package.xml b/sensing/autoware_radar_scan_to_pointcloud2/package.xml index bd0ed8ee717db..9dae0e583bc43 100644 --- a/sensing/autoware_radar_scan_to_pointcloud2/package.xml +++ b/sensing/autoware_radar_scan_to_pointcloud2/package.xml @@ -1,7 +1,7 @@ autoware_radar_scan_to_pointcloud2 - 0.38.0 + 0.39.0 autoware_radar_scan_to_pointcloud2 Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst b/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst index c7ee62041f611..eba58b0fb6278 100644 --- a/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_static_pointcloud_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_radar_static_pointcloud_filter/package.xml b/sensing/autoware_radar_static_pointcloud_filter/package.xml index 744148517aafe..f685147f9d0a4 100644 --- a/sensing/autoware_radar_static_pointcloud_filter/package.xml +++ b/sensing/autoware_radar_static_pointcloud_filter/package.xml @@ -1,7 +1,7 @@ autoware_radar_static_pointcloud_filter - 0.38.0 + 0.39.0 autoware_radar_static_pointcloud_filter Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_threshold_filter/CHANGELOG.rst b/sensing/autoware_radar_threshold_filter/CHANGELOG.rst index 366301da6ea56..ef65bcc5f4fe4 100644 --- a/sensing/autoware_radar_threshold_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_threshold_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_threshold_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_radar_threshold_filter/package.xml b/sensing/autoware_radar_threshold_filter/package.xml index 7629ffec9b96a..3127153fd9e30 100644 --- a/sensing/autoware_radar_threshold_filter/package.xml +++ b/sensing/autoware_radar_threshold_filter/package.xml @@ -1,7 +1,7 @@ autoware_radar_threshold_filter - 0.38.0 + 0.39.0 autoware_radar_threshold_filter Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst b/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst index 6bc3742acd7fc..29ff75fddd69a 100644 --- a/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_radar_tracks_noise_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_radar_tracks_noise_filter/package.xml b/sensing/autoware_radar_tracks_noise_filter/package.xml index 8b08507326c98..af8db58a86567 100644 --- a/sensing/autoware_radar_tracks_noise_filter/package.xml +++ b/sensing/autoware_radar_tracks_noise_filter/package.xml @@ -2,7 +2,7 @@ autoware_radar_tracks_noise_filter - 0.38.0 + 0.39.0 autoware_radar_tracks_noise_filter Sathshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst b/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst index b2488806af1ba..9f4f9e3e96395 100644 --- a/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst +++ b/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package vehicle_velocity_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/autoware_vehicle_velocity_converter/package.xml b/sensing/autoware_vehicle_velocity_converter/package.xml index 323002396c841..ce4e36855a03a 100644 --- a/sensing/autoware_vehicle_velocity_converter/package.xml +++ b/sensing/autoware_vehicle_velocity_converter/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_velocity_converter - 0.38.0 + 0.39.0 The autoware_vehicle_velocity_converter package Ryu Yamamoto Apache License 2.0 diff --git a/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst b/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst index 4b0c42f440fa2..1721bb0e74007 100644 --- a/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst +++ b/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_livox_tag_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/sensing/livox/autoware_livox_tag_filter/package.xml b/sensing/livox/autoware_livox_tag_filter/package.xml index 43a4de255d9da..adb2229745789 100644 --- a/sensing/livox/autoware_livox_tag_filter/package.xml +++ b/sensing/livox/autoware_livox_tag_filter/package.xml @@ -2,7 +2,7 @@ autoware_livox_tag_filter - 0.38.0 + 0.39.0 The autoware_livox_tag_filter package Ryohsuke Mitsudome Kenzo Lobos-Tsunekawa diff --git a/simulator/autoware_carla_interface/CHANGELOG.rst b/simulator/autoware_carla_interface/CHANGELOG.rst index dee9f80052a1d..bdc1cc41bd5e0 100644 --- a/simulator/autoware_carla_interface/CHANGELOG.rst +++ b/simulator/autoware_carla_interface/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_carla_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/simulator/autoware_carla_interface/package.xml b/simulator/autoware_carla_interface/package.xml index d71f4d0d85924..215a7c778523f 100644 --- a/simulator/autoware_carla_interface/package.xml +++ b/simulator/autoware_carla_interface/package.xml @@ -1,7 +1,7 @@ autoware_carla_interface - 0.38.0 + 0.39.0 The carla autoware bridge package Muhammad Raditya GIOVANNI Maxime CLEMENT diff --git a/simulator/dummy_perception_publisher/CHANGELOG.rst b/simulator/dummy_perception_publisher/CHANGELOG.rst index 102616f3409d9..d0483f9ebe480 100644 --- a/simulator/dummy_perception_publisher/CHANGELOG.rst +++ b/simulator/dummy_perception_publisher/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package dummy_perception_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/simulator/dummy_perception_publisher/package.xml b/simulator/dummy_perception_publisher/package.xml index 09c4cc63de67b..f2b60ce3ef857 100644 --- a/simulator/dummy_perception_publisher/package.xml +++ b/simulator/dummy_perception_publisher/package.xml @@ -2,7 +2,7 @@ dummy_perception_publisher - 0.38.0 + 0.39.0 The dummy_perception_publisher package Yukihiro Saito Apache License 2.0 diff --git a/simulator/fault_injection/CHANGELOG.rst b/simulator/fault_injection/CHANGELOG.rst index f62dd6c5cbc69..74ec3b4a867f4 100644 --- a/simulator/fault_injection/CHANGELOG.rst +++ b/simulator/fault_injection/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package fault_injection ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/simulator/fault_injection/package.xml b/simulator/fault_injection/package.xml index 7e432357139d4..25a5ceddd31be 100644 --- a/simulator/fault_injection/package.xml +++ b/simulator/fault_injection/package.xml @@ -2,7 +2,7 @@ fault_injection - 0.38.0 + 0.39.0 fault_injection Keisuke Shima Apache License 2.0 diff --git a/simulator/learning_based_vehicle_model/CHANGELOG.rst b/simulator/learning_based_vehicle_model/CHANGELOG.rst index 183535778ffec..b902713689ab1 100644 --- a/simulator/learning_based_vehicle_model/CHANGELOG.rst +++ b/simulator/learning_based_vehicle_model/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package learning_based_vehicle_model ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/simulator/learning_based_vehicle_model/package.xml b/simulator/learning_based_vehicle_model/package.xml index c09d152c432cb..11b5b2f88db03 100644 --- a/simulator/learning_based_vehicle_model/package.xml +++ b/simulator/learning_based_vehicle_model/package.xml @@ -2,7 +2,7 @@ learning_based_vehicle_model - 0.38.0 + 0.39.0 learning_based_vehicle_model for simple_planning_simulator Maxime Clement Tomas Nagy diff --git a/simulator/simple_planning_simulator/CHANGELOG.rst b/simulator/simple_planning_simulator/CHANGELOG.rst index 76c12ecf37f41..7b995d36dbf83 100644 --- a/simulator/simple_planning_simulator/CHANGELOG.rst +++ b/simulator/simple_planning_simulator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package simple_planning_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index a81f9e2147bab..a6f86dd6e8a4b 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -2,7 +2,7 @@ simple_planning_simulator - 0.38.0 + 0.39.0 simple_planning_simulator as a ROS 2 node Takamasa Horibe Tomoya Kimura diff --git a/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst b/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst index df41afe78a70f..1d5b1d454a4a7 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst +++ b/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package tier4_dummy_object_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(tier4_dummy_object_rviz_plugin): fix missing dependency (`#9306 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/simulator/tier4_dummy_object_rviz_plugin/package.xml b/simulator/tier4_dummy_object_rviz_plugin/package.xml index c3d8f78670502..c5ef8a68eb98f 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/package.xml +++ b/simulator/tier4_dummy_object_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_dummy_object_rviz_plugin - 0.38.0 + 0.39.0 The tier4_dummy_object_rviz_plugin package Yukihiro Saito Apache License 2.0 diff --git a/simulator/vehicle_door_simulator/CHANGELOG.rst b/simulator/vehicle_door_simulator/CHANGELOG.rst index d825a300763f4..105292a8e63e1 100644 --- a/simulator/vehicle_door_simulator/CHANGELOG.rst +++ b/simulator/vehicle_door_simulator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package vehicle_door_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/simulator/vehicle_door_simulator/package.xml b/simulator/vehicle_door_simulator/package.xml index b500940602ce2..008fcb9500bfe 100644 --- a/simulator/vehicle_door_simulator/package.xml +++ b/simulator/vehicle_door_simulator/package.xml @@ -2,7 +2,7 @@ vehicle_door_simulator - 0.38.0 + 0.39.0 The vehicle_door_simulator package Takagi, Isamu Apache License 2.0 diff --git a/system/autoware_component_monitor/CHANGELOG.rst b/system/autoware_component_monitor/CHANGELOG.rst index 30c97e6f41adc..224edb28d1c45 100644 --- a/system/autoware_component_monitor/CHANGELOG.rst +++ b/system/autoware_component_monitor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_component_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/autoware_component_monitor/package.xml b/system/autoware_component_monitor/package.xml index 92f2fa51f704e..5655c495b0aa7 100644 --- a/system/autoware_component_monitor/package.xml +++ b/system/autoware_component_monitor/package.xml @@ -2,7 +2,7 @@ autoware_component_monitor - 0.38.0 + 0.39.0 A ROS 2 package to monitor system usage of component containers. Mehmet Emin Başoğlu Barış Zeren diff --git a/system/autoware_default_adapi/CHANGELOG.rst b/system/autoware_default_adapi/CHANGELOG.rst index 295b95531177f..64f7326264a58 100644 --- a/system/autoware_default_adapi/CHANGELOG.rst +++ b/system/autoware_default_adapi/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_default_adapi ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_default_adapi): change subscribing steering factor topic name for obstacle avoidance and lane changes (`#9273 `_) + feat(planning): add new steering factor topics for obstacle avoidance and lane changes +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Kyoichi Sugahara, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/autoware_default_adapi/package.xml b/system/autoware_default_adapi/package.xml index f664f72234f9f..d04c476a45ae7 100644 --- a/system/autoware_default_adapi/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -2,7 +2,7 @@ autoware_default_adapi - 0.38.0 + 0.39.0 The autoware_default_adapi package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/autoware_processing_time_checker/CHANGELOG.rst b/system/autoware_processing_time_checker/CHANGELOG.rst index 672a5db25e31c..96df106a6e4eb 100644 --- a/system/autoware_processing_time_checker/CHANGELOG.rst +++ b/system/autoware_processing_time_checker/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package autoware_processing_time_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Kem (TiankuiXian), Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/autoware_processing_time_checker/package.xml b/system/autoware_processing_time_checker/package.xml index 16b225f3ef425..17b4599197407 100644 --- a/system/autoware_processing_time_checker/package.xml +++ b/system/autoware_processing_time_checker/package.xml @@ -2,7 +2,7 @@ autoware_processing_time_checker - 0.38.0 + 0.39.0 A package to find out nodes with common names Takayuki Murooka Kosuke Takeuchi diff --git a/system/bluetooth_monitor/CHANGELOG.rst b/system/bluetooth_monitor/CHANGELOG.rst index ca70113c03740..96056c8907c86 100644 --- a/system/bluetooth_monitor/CHANGELOG.rst +++ b/system/bluetooth_monitor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package bluetooth_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/bluetooth_monitor/package.xml b/system/bluetooth_monitor/package.xml index 4f6b9f38f7cb3..dfa77dd303427 100644 --- a/system/bluetooth_monitor/package.xml +++ b/system/bluetooth_monitor/package.xml @@ -2,7 +2,7 @@ bluetooth_monitor - 0.38.0 + 0.39.0 Bluetooth alive monitoring Fumihito Ito Apache License 2.0 diff --git a/system/component_state_monitor/CHANGELOG.rst b/system/component_state_monitor/CHANGELOG.rst index 751b67a25a6e4..97281628626c3 100644 --- a/system/component_state_monitor/CHANGELOG.rst +++ b/system/component_state_monitor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package component_state_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/component_state_monitor/package.xml b/system/component_state_monitor/package.xml index 9e4d77878941a..60dde0d93581b 100644 --- a/system/component_state_monitor/package.xml +++ b/system/component_state_monitor/package.xml @@ -2,7 +2,7 @@ component_state_monitor - 0.38.0 + 0.39.0 The component_state_monitor package Takagi, Isamu Apache License 2.0 diff --git a/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst b/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst index 4c4f7943578bb..c60bb8204eb3e 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst +++ b/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package ad_api_adaptors ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/default_ad_api_helpers/ad_api_adaptors/package.xml b/system/default_ad_api_helpers/ad_api_adaptors/package.xml index f6210809122de..c91edb9232444 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/package.xml +++ b/system/default_ad_api_helpers/ad_api_adaptors/package.xml @@ -2,7 +2,7 @@ ad_api_adaptors - 0.38.0 + 0.39.0 The ad_api_adaptors package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst b/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst index bea6efd9c2fe3..5961ee96c28d1 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst +++ b/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package ad_api_visualizers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/default_ad_api_helpers/ad_api_visualizers/package.xml b/system/default_ad_api_helpers/ad_api_visualizers/package.xml index ab7d2ec4a5799..b05fe7222b923 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/package.xml +++ b/system/default_ad_api_helpers/ad_api_visualizers/package.xml @@ -2,7 +2,7 @@ ad_api_visualizers - 0.38.0 + 0.39.0 The ad_api_visualizers package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/default_ad_api_helpers/ad_api_visualizers/setup.py b/system/default_ad_api_helpers/ad_api_visualizers/setup.py index fe2fdd46463e3..b088271ba74a7 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/setup.py +++ b/system/default_ad_api_helpers/ad_api_visualizers/setup.py @@ -11,7 +11,7 @@ setup( name=package_name, - version="0.38.0", + version="0.39.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", [f"resource/{package_name}"]), diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst b/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst index 1e08d0eff6194..795fe18c58e29 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst +++ b/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package automatic_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml index 0f665cfc4f948..7a0566f478118 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml +++ b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml @@ -2,7 +2,7 @@ automatic_pose_initializer - 0.38.0 + 0.39.0 The automatic_pose_initializer package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/diagnostic_graph_aggregator/CHANGELOG.rst b/system/diagnostic_graph_aggregator/CHANGELOG.rst index 2398f0bb7f37f..c3824be814e01 100644 --- a/system/diagnostic_graph_aggregator/CHANGELOG.rst +++ b/system/diagnostic_graph_aggregator/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package diagnostic_graph_aggregator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(diagnostic_graph_aggregator): implement diagnostic graph dump functionality (`#9261 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/diagnostic_graph_aggregator/package.xml b/system/diagnostic_graph_aggregator/package.xml index bee03ba087e83..0b58afa330f43 100644 --- a/system/diagnostic_graph_aggregator/package.xml +++ b/system/diagnostic_graph_aggregator/package.xml @@ -2,7 +2,7 @@ diagnostic_graph_aggregator - 0.38.0 + 0.39.0 The diagnostic_graph_aggregator package Takagi, Isamu Apache License 2.0 diff --git a/system/diagnostic_graph_utils/CHANGELOG.rst b/system/diagnostic_graph_utils/CHANGELOG.rst index 8d1a7606444d3..17643d9e955e5 100644 --- a/system/diagnostic_graph_utils/CHANGELOG.rst +++ b/system/diagnostic_graph_utils/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package diagnostic_graph_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(diagnostic_graph_utils): reset graph when new one is received (`#9208 `_) + fix(diagnostic_graph_utils): reset graph when new one is reveived +* Contributors: Esteve Fernandez, Takagi, Isamu, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml index 2b393b4191581..d558ba26b636a 100644 --- a/system/diagnostic_graph_utils/package.xml +++ b/system/diagnostic_graph_utils/package.xml @@ -2,7 +2,7 @@ diagnostic_graph_utils - 0.38.0 + 0.39.0 The diagnostic_graph_utils package Takagi, Isamu Apache License 2.0 diff --git a/system/dummy_diag_publisher/CHANGELOG.rst b/system/dummy_diag_publisher/CHANGELOG.rst index 1fef1964efc56..7f50608ce061b 100644 --- a/system/dummy_diag_publisher/CHANGELOG.rst +++ b/system/dummy_diag_publisher/CHANGELOG.rst @@ -2,6 +2,28 @@ Changelog for package dummy_diag_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(dummy_diag_publisher): not use diagnostic_updater and param callback (`#9257 `_) + * fix(dummy_diag_publisher): not use diagnostic_updater and param callback for v0.29.0 (`#1414 `_) + fix(dummy_diag_publisher): not use diagnostic_updater and param callback + Co-authored-by: h-ohta + * fix: resolve build error of dummy diag publisher (`#1415 `_) + fix merge conflict + --------- + Co-authored-by: Shohei Sakai + Co-authored-by: h-ohta +* Contributors: Esteve Fernandez, Yuki TAKAGI, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/dummy_diag_publisher/package.xml b/system/dummy_diag_publisher/package.xml index 6029314232100..d5693da6db8c6 100644 --- a/system/dummy_diag_publisher/package.xml +++ b/system/dummy_diag_publisher/package.xml @@ -2,7 +2,7 @@ dummy_diag_publisher - 0.38.0 + 0.39.0 The dummy_diag_publisher ROS 2 package Fumihito Ito TetsuKawa diff --git a/system/dummy_infrastructure/CHANGELOG.rst b/system/dummy_infrastructure/CHANGELOG.rst index 25c3bf5d0f6a3..e7ce27fe644e7 100644 --- a/system/dummy_infrastructure/CHANGELOG.rst +++ b/system/dummy_infrastructure/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package dummy_infrastructure ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/dummy_infrastructure/package.xml b/system/dummy_infrastructure/package.xml index 431845825f3d5..b72927cd47162 100644 --- a/system/dummy_infrastructure/package.xml +++ b/system/dummy_infrastructure/package.xml @@ -2,7 +2,7 @@ dummy_infrastructure - 0.38.0 + 0.39.0 dummy_infrastructure Ryohsuke Mitsudome Apache License 2.0 diff --git a/system/duplicated_node_checker/CHANGELOG.rst b/system/duplicated_node_checker/CHANGELOG.rst index 406406b49daeb..d44d9508aac6c 100644 --- a/system/duplicated_node_checker/CHANGELOG.rst +++ b/system/duplicated_node_checker/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package duplicated_node_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/duplicated_node_checker/package.xml b/system/duplicated_node_checker/package.xml index 5b699d014b5f0..12eb39f8ead30 100644 --- a/system/duplicated_node_checker/package.xml +++ b/system/duplicated_node_checker/package.xml @@ -2,7 +2,7 @@ duplicated_node_checker - 0.38.0 + 0.39.0 A package to find out nodes with common names Shumpei Wakabayashi yliuhb diff --git a/system/hazard_status_converter/CHANGELOG.rst b/system/hazard_status_converter/CHANGELOG.rst index c0f54a85f3b27..d3f4488b00836 100644 --- a/system/hazard_status_converter/CHANGELOG.rst +++ b/system/hazard_status_converter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package hazard_status_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/hazard_status_converter/package.xml b/system/hazard_status_converter/package.xml index 7d154abb7b26c..e53847459ea39 100644 --- a/system/hazard_status_converter/package.xml +++ b/system/hazard_status_converter/package.xml @@ -2,7 +2,7 @@ hazard_status_converter - 0.38.0 + 0.39.0 The hazard_status_converter package Takagi, Isamu Apache License 2.0 diff --git a/system/mrm_comfortable_stop_operator/CHANGELOG.rst b/system/mrm_comfortable_stop_operator/CHANGELOG.rst index 1da165fc4b710..fc403b6a366ff 100644 --- a/system/mrm_comfortable_stop_operator/CHANGELOG.rst +++ b/system/mrm_comfortable_stop_operator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package mrm_comfortable_stop_operator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/mrm_comfortable_stop_operator/package.xml b/system/mrm_comfortable_stop_operator/package.xml index 92a9569bf329a..ec8508f691439 100644 --- a/system/mrm_comfortable_stop_operator/package.xml +++ b/system/mrm_comfortable_stop_operator/package.xml @@ -2,7 +2,7 @@ mrm_comfortable_stop_operator - 0.38.0 + 0.39.0 The MRM comfortable stop operator package Makoto Kurihara Tomohito Ando diff --git a/system/mrm_emergency_stop_operator/CHANGELOG.rst b/system/mrm_emergency_stop_operator/CHANGELOG.rst index e8a4611e43299..6ace9fa84cc90 100644 --- a/system/mrm_emergency_stop_operator/CHANGELOG.rst +++ b/system/mrm_emergency_stop_operator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package mrm_emergency_stop_operator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/mrm_emergency_stop_operator/package.xml b/system/mrm_emergency_stop_operator/package.xml index 402a94f305cfe..8be2e83484c17 100644 --- a/system/mrm_emergency_stop_operator/package.xml +++ b/system/mrm_emergency_stop_operator/package.xml @@ -2,7 +2,7 @@ mrm_emergency_stop_operator - 0.38.0 + 0.39.0 The MRM emergency stop operator package Makoto Kurihara Tomohito Ando diff --git a/system/mrm_handler/CHANGELOG.rst b/system/mrm_handler/CHANGELOG.rst index 92b7cb8a59351..4792246b01e86 100644 --- a/system/mrm_handler/CHANGELOG.rst +++ b/system/mrm_handler/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package mrm_handler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/mrm_handler/package.xml b/system/mrm_handler/package.xml index 93959a6931794..78d6b631799bf 100644 --- a/system/mrm_handler/package.xml +++ b/system/mrm_handler/package.xml @@ -2,7 +2,7 @@ mrm_handler - 0.38.0 + 0.39.0 The mrm_handler ROS 2 package Makoto Kurihara Ryuta Kambe diff --git a/system/system_diagnostic_monitor/CHANGELOG.rst b/system/system_diagnostic_monitor/CHANGELOG.rst index f25eab5c7fed4..faf15ad273924 100644 --- a/system/system_diagnostic_monitor/CHANGELOG.rst +++ b/system/system_diagnostic_monitor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package system_diagnostic_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/system_diagnostic_monitor/package.xml b/system/system_diagnostic_monitor/package.xml index 54031a2e82daa..657268589c5a2 100644 --- a/system/system_diagnostic_monitor/package.xml +++ b/system/system_diagnostic_monitor/package.xml @@ -2,7 +2,7 @@ system_diagnostic_monitor - 0.38.0 + 0.39.0 The system_diagnostic_monitor package Takagi, Isamu Apache License 2.0 diff --git a/system/system_monitor/CHANGELOG.rst b/system/system_monitor/CHANGELOG.rst index b5c97c09e28df..7759f315830d2 100644 --- a/system/system_monitor/CHANGELOG.rst +++ b/system/system_monitor/CHANGELOG.rst @@ -2,6 +2,28 @@ Changelog for package system_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(system_monitor): add on/off config for network traffic monitor (`#9069 `_) + * feat(system_monitor): add config for network traffic monitor + * fix: change function name from stop to skip + --------- +* feat(system_monitor): support loopback network interface (`#9067 `_) + * feat(system_monitor): support loopback network interface + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Yutaka Kondo, iwatake + 0.38.0 (2024-11-08) ------------------- * remove system_monitor/CHANGELOG.rst diff --git a/system/system_monitor/package.xml b/system/system_monitor/package.xml index e1a872812660d..1044cb2fde474 100644 --- a/system/system_monitor/package.xml +++ b/system/system_monitor/package.xml @@ -2,7 +2,7 @@ system_monitor - 0.38.0 + 0.39.0 The system_monitor package Fumihito Ito TetsuKawa diff --git a/system/topic_state_monitor/CHANGELOG.rst b/system/topic_state_monitor/CHANGELOG.rst index 8c636a421375c..6f7c71abcf683 100644 --- a/system/topic_state_monitor/CHANGELOG.rst +++ b/system/topic_state_monitor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package topic_state_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/topic_state_monitor/package.xml b/system/topic_state_monitor/package.xml index d0521145b9fec..b6e517aec34bb 100644 --- a/system/topic_state_monitor/package.xml +++ b/system/topic_state_monitor/package.xml @@ -2,7 +2,7 @@ topic_state_monitor - 0.38.0 + 0.39.0 The topic_state_monitor package Ryohsuke Mitsudome Apache License 2.0 diff --git a/system/velodyne_monitor/CHANGELOG.rst b/system/velodyne_monitor/CHANGELOG.rst index ca10466633e36..717865b43d5ea 100644 --- a/system/velodyne_monitor/CHANGELOG.rst +++ b/system/velodyne_monitor/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package velodyne_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/system/velodyne_monitor/package.xml b/system/velodyne_monitor/package.xml index c37dac15a48aa..665e6ab87c575 100644 --- a/system/velodyne_monitor/package.xml +++ b/system/velodyne_monitor/package.xml @@ -2,7 +2,7 @@ velodyne_monitor - 0.38.0 + 0.39.0 The velodyne_monitor package Fumihito Ito Apache License 2.0 diff --git a/tools/reaction_analyzer/CHANGELOG.rst b/tools/reaction_analyzer/CHANGELOG.rst index 81084ba8724c4..740affa42f42a 100644 --- a/tools/reaction_analyzer/CHANGELOG.rst +++ b/tools/reaction_analyzer/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package reaction_analyzer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/tools/reaction_analyzer/package.xml b/tools/reaction_analyzer/package.xml index 8ec8f924edc1f..b3b1f69421fe7 100644 --- a/tools/reaction_analyzer/package.xml +++ b/tools/reaction_analyzer/package.xml @@ -2,7 +2,7 @@ reaction_analyzer - 0.38.0 + 0.39.0 Analyzer that measures reaction times of the nodes Berkay Karaman diff --git a/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst b/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst index 1c025329b3417..b53b0b225a141 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst +++ b/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_accel_brake_map_calibrator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/vehicle/autoware_accel_brake_map_calibrator/package.xml b/vehicle/autoware_accel_brake_map_calibrator/package.xml index ef8ebb9df5625..00ed9af04e5da 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/package.xml +++ b/vehicle/autoware_accel_brake_map_calibrator/package.xml @@ -2,7 +2,7 @@ autoware_accel_brake_map_calibrator - 0.38.0 + 0.39.0 The accel_brake_map_calibrator Tomoya Kimura Taiki Tanaka diff --git a/vehicle/autoware_external_cmd_converter/CHANGELOG.rst b/vehicle/autoware_external_cmd_converter/CHANGELOG.rst index 058678773d251..7c1df55f31c03 100644 --- a/vehicle/autoware_external_cmd_converter/CHANGELOG.rst +++ b/vehicle/autoware_external_cmd_converter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_external_cmd_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/vehicle/autoware_external_cmd_converter/package.xml b/vehicle/autoware_external_cmd_converter/package.xml index 35003f624c704..146327e6ca4b4 100644 --- a/vehicle/autoware_external_cmd_converter/package.xml +++ b/vehicle/autoware_external_cmd_converter/package.xml @@ -2,7 +2,7 @@ autoware_external_cmd_converter - 0.38.0 + 0.39.0 The autoware_external_cmd_converter package Takamasa Horibe Eiki Nagata diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst b/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst index 483f8cbd12c60..5c9572a7b712d 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst +++ b/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_raw_vehicle_cmd_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml index 41bbff445ba7e..1e3b265127a63 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml +++ b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml @@ -2,7 +2,7 @@ autoware_raw_vehicle_cmd_converter - 0.38.0 + 0.39.0 The autoware_raw_vehicle_cmd_converter package Takamasa Horibe Tanaka Taiki diff --git a/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst b/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst index 9a421dc7a35bf..8838f8de5c5d5 100644 --- a/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst +++ b/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst @@ -2,6 +2,18 @@ Changelog for package autoware_steer_offset_estimator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.39.0 (2024-11-25) +------------------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Yutaka Kondo + 0.38.0 (2024-11-08) ------------------- * unify package.xml version to 0.37.0 diff --git a/vehicle/autoware_steer_offset_estimator/package.xml b/vehicle/autoware_steer_offset_estimator/package.xml index 27096dd20ab28..e3e633562b98a 100644 --- a/vehicle/autoware_steer_offset_estimator/package.xml +++ b/vehicle/autoware_steer_offset_estimator/package.xml @@ -1,7 +1,7 @@ autoware_steer_offset_estimator - 0.38.0 + 0.39.0 The steer_offset_estimator Taiki Tanaka Apache License 2.0 From 90bf2d07efebba88571e6e6218fa34a70ce85044 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sat, 7 Dec 2024 17:35:31 +0900 Subject: [PATCH 252/273] fix(goal_planner): fix isStopped judgement (#9585) * fix(goal_planner): fix isStopped judgement Signed-off-by: kosuke55 * fix typo Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner_module.hpp | 3 ++- .../src/goal_planner_module.cpp | 15 ++++++++++----- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 914da46e60180..09acced162abd 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -158,7 +158,8 @@ bool checkOccupancyGridCollision( bool isStopped( std::deque & odometry_buffer, - const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower); + const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower, + const double velocity_upper); // Flag class for managing whether a certain callback is running in multi-threading class ScopedFlag diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 01d06a4964c61..716047c7ad1f1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -244,7 +244,8 @@ bool checkOccupancyGridCollision( bool isStopped( std::deque & odometry_buffer, - const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower) + const nav_msgs::msg::Odometry::ConstSharedPtr self_odometry, const double duration_lower, + const double velocity_upper) { odometry_buffer.push_back(self_odometry); // Delete old data in buffer_stuck_ @@ -259,7 +260,7 @@ bool isStopped( bool is_stopped = true; for (const auto & odometry : odometry_buffer) { const double ego_vel = utils::l2Norm(odometry->twist.twist.linear); - if (ego_vel > duration_lower) { + if (ego_vel > velocity_upper) { is_stopped = false; break; } @@ -879,7 +880,8 @@ bool GoalPlannerModule::canReturnToLaneParking(const PullOverContextData & conte { // return only before starting free space parking if (!isStopped( - odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time)) { + odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time, + parameters_->th_stopped_velocity)) { return false; } @@ -1760,7 +1762,9 @@ bool GoalPlannerModule::isStuck( } constexpr double stuck_time = 5.0; - if (!isStopped(odometry_buffer_stuck_, planner_data->self_odometry, stuck_time)) { + if (!isStopped( + odometry_buffer_stuck_, planner_data->self_odometry, stuck_time, + parameters_->th_stopped_velocity)) { return false; } @@ -1801,7 +1805,8 @@ bool GoalPlannerModule::hasFinishedCurrentPath(const PullOverContextData & ctx_d } if (!isStopped( - odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time)) { + odometry_buffer_stopped_, planner_data_->self_odometry, parameters_->th_stopped_time, + parameters_->th_stopped_velocity)) { return false; } From 47bbb1cf035c69ab8b9bf2eff87b268b5d37d985 Mon Sep 17 00:00:00 2001 From: Ryuta Kambe Date: Mon, 9 Dec 2024 10:40:58 +0900 Subject: [PATCH 253/273] fix(autoware_behavior_velocity_stop_line_module): remove unused function (#9591) Signed-off-by: Ryuta Kambe --- .../src/scene.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp index 4d8dea94583bb..2a9c5dab1ebd9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp @@ -26,15 +26,6 @@ namespace autoware::behavior_velocity_planner { -geometry_msgs::msg::Point getCenterOfStopLine(const lanelet::ConstLineString3d & stop_line) -{ - geometry_msgs::msg::Point center_point; - center_point.x = (stop_line[0].x() + stop_line[1].x()) / 2.0; - center_point.y = (stop_line[0].y() + stop_line[1].y()) / 2.0; - center_point.z = (stop_line[0].z() + stop_line[1].z()) / 2.0; - return center_point; -} - StopLineModule::StopLineModule( const int64_t module_id, lanelet::ConstLineString3d stop_line, const PlannerParam & planner_param, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock) From 9553414c614009ca8db33521d4a1a68e430cce7a Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Mon, 9 Dec 2024 12:05:38 +0900 Subject: [PATCH 254/273] fix(autoware_image_projection_based_fusion): detected object roi box projection fix (#9519) * fix: detected object roi box projection fix 1. eliminate misuse of std::numeric_limits::min() 2. fix roi range up to the image edges Signed-off-by: Taekjin LEE * fix: fix roi range calculation in RoiDetectedObjectFusionNode Improve the calculation of the region of interest (ROI) in the RoiDetectedObjectFusionNode. The previous code had an issue where the ROI range was not correctly limited to the image edges. This fix ensures that the ROI is within the image boundaries by using the correct comparison operators for the x and y coordinates. Signed-off-by: Taekjin LEE --------- Signed-off-by: Taekjin LEE --- .../src/roi_detected_object_fusion/node.cpp | 25 ++++++++----------- 1 file changed, 11 insertions(+), 14 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp index 134dd7bad9129..3ef3af8168f53 100644 --- a/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp @@ -146,8 +146,7 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( transformPoints(vertices, object2camera_affine, vertices_camera_coord); } - double min_x(std::numeric_limits::max()), min_y(std::numeric_limits::max()), - max_x(std::numeric_limits::min()), max_y(std::numeric_limits::min()); + double min_x(image_width), min_y(image_height), max_x(0.0), max_y(0.0); std::size_t point_on_image_cnt = 0; for (const auto & point : vertices_camera_coord) { if (point.z() <= 0.0) { @@ -164,8 +163,8 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( max_y = std::max(proj_point.y(), max_y); if ( - proj_point.x() >= 0 && proj_point.x() <= image_width - 1 && proj_point.y() >= 0 && - proj_point.y() <= image_height - 1) { + proj_point.x() >= 0 && proj_point.x() < image_width && proj_point.y() >= 0 && + proj_point.y() < image_height) { point_on_image_cnt++; if (debugger_) { @@ -177,18 +176,16 @@ RoiDetectedObjectFusionNode::generateDetectedObjectRoIs( continue; } - min_x = std::max(min_x, 0.0); - min_y = std::max(min_y, 0.0); - max_x = std::min(max_x, image_width - 1); - max_y = std::min(max_y, image_height - 1); + const uint32_t idx_min_x = std::floor(std::max(min_x, 0.0)); + const uint32_t idx_min_y = std::floor(std::max(min_y, 0.0)); + const uint32_t idx_max_x = std::ceil(std::min(max_x, image_width)); + const uint32_t idx_max_y = std::ceil(std::min(max_y, image_height)); DetectedObjectWithFeature object_roi; - object_roi.feature.roi.x_offset = static_cast(min_x); - object_roi.feature.roi.y_offset = static_cast(min_y); - object_roi.feature.roi.width = - static_cast(max_x) - static_cast(min_x); - object_roi.feature.roi.height = - static_cast(max_y) - static_cast(min_y); + object_roi.feature.roi.x_offset = idx_min_x; + object_roi.feature.roi.y_offset = idx_min_y; + object_roi.feature.roi.width = idx_max_x - idx_min_x; + object_roi.feature.roi.height = idx_max_y - idx_min_y; object_roi.object = object; object_roi_map.insert(std::make_pair(obj_i, object_roi)); From dbdf9a16d83267c4d9a5f99b0e442c9f997ab2c7 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Mon, 9 Dec 2024 21:26:07 +0900 Subject: [PATCH 255/273] fix(lane_change): check obj predicted path when filtering (#9385) * RT1-8537 check object's predicted path when filtering Signed-off-by: Zulfaqar Azmi * use ranges view in get_line_string_paths Signed-off-by: Zulfaqar Azmi * check only vehicle type predicted path Signed-off-by: Zulfaqar Azmi * Refactor naming Signed-off-by: Zulfaqar Azmi * fix grammatical Signed-off-by: Zulfaqar Azmi * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> * precommit and grammar fix Signed-off-by: Zulfaqar Azmi --------- Signed-off-by: Zulfaqar Azmi Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> --- .../utils/utils.hpp | 17 ++++++++++ .../src/scene.cpp | 1 + .../src/utils/utils.cpp | 34 +++++++++++-------- .../path_safety_checker/objects_filtering.hpp | 10 ++++++ .../path_safety_checker/objects_filtering.cpp | 14 ++++++++ 5 files changed, 62 insertions(+), 14 deletions(-) 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 7c1c8e2c65abe..5dcd132f16377 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 @@ -382,5 +382,22 @@ bool filter_target_lane_objects( const double dist_ego_to_current_lanes_center, const bool ahead_of_ego, const bool before_terminal, TargetLaneLeadingObjects & leading_objects, ExtendedPredictedObjects & trailing_objects); + +/** + * @brief Determines if the object's predicted path overlaps with the given lane polygon. + * + * This function checks whether any of the line string paths derived from the object's predicted + * trajectories intersect or overlap with the specified polygon representing lanes. + * + * @param object The extended predicted object containing predicted trajectories and initial + * polygon. + * @param lanes_polygon A polygon representing the lanes to check for overlaps with the object's + * paths. + * + * @return true if any of the object's predicted paths overlap with the lanes polygon, false + * otherwise. + */ +bool object_path_overlaps_lanes( + const ExtendedPredictedObject & object, const lanelet::BasicPolygon2d & lanes_polygon); } // namespace autoware::behavior_path_planner::utils::lane_change #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_ 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 99e7cc73e59ff..2770831dbc485 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 @@ -988,6 +988,7 @@ lane_change::TargetObjects NormalLaneChange::get_target_objects( FilteredLanesObjects NormalLaneChange::filter_objects() const { + universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); auto objects = *planner_data_->dynamic_object; utils::path_safety_checker::filterObjectsByClass( objects, lane_change_parameters_->safety.target_object_types); 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 9ab6ac288dfd4..4d46f8270fac3 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 @@ -35,6 +35,8 @@ #include #include #include +#include +#include #include #include @@ -1149,11 +1151,8 @@ std::vector get_line_string_paths(const ExtendedPredictedObject & return line_string; }; - const auto paths = object.predicted_paths; - std::vector line_strings; - std::transform(paths.begin(), paths.end(), std::back_inserter(line_strings), to_linestring_2d); - - return line_strings; + return object.predicted_paths | ranges::views::transform(to_linestring_2d) | + ranges::to(); } bool has_overtaking_turn_lane_object( @@ -1164,10 +1163,6 @@ bool has_overtaking_turn_lane_object( return false; } - const auto is_path_overlap_with_target = [&](const LineString2d & path) { - return !boost::geometry::disjoint(path, common_data_ptr->lanes_polygon_ptr->target); - }; - const auto is_object_overlap_with_target = [&](const auto & object) { // to compensate for perception issue, or if object is from behind ego, and tries to overtake, // but stop all of sudden @@ -1176,8 +1171,7 @@ bool has_overtaking_turn_lane_object( return true; } - const auto paths = get_line_string_paths(object); - return std::any_of(paths.begin(), paths.end(), is_path_overlap_with_target); + return object_path_overlaps_lanes(object, common_data_ptr->lanes_polygon_ptr->target); }; return std::any_of( @@ -1190,6 +1184,7 @@ bool filter_target_lane_objects( const bool before_terminal, TargetLaneLeadingObjects & leading_objects, ExtendedPredictedObjects & trailing_objects) { + using behavior_path_planner::utils::path_safety_checker::filter::is_vehicle; using behavior_path_planner::utils::path_safety_checker::filter::velocity_filter; const auto & current_lanes = common_data_ptr->lanes_ptr->current; const auto & vehicle_width = common_data_ptr->bpp_param_ptr->vehicle_info.vehicle_width_m; @@ -1206,9 +1201,12 @@ bool filter_target_lane_objects( const auto is_stopped = velocity_filter( object.initial_twist, -std::numeric_limits::epsilon(), stopped_obj_vel_th); if (is_lateral_far && before_terminal) { - const auto in_target_lanes = - !boost::geometry::disjoint(object.initial_polygon, lanes_polygon.target); - if (in_target_lanes) { + const auto overlapping_with_target_lanes = + !boost::geometry::disjoint(object.initial_polygon, lanes_polygon.target) || + (!is_stopped && is_vehicle(object.classification) && + object_path_overlaps_lanes(object, lanes_polygon.target)); + + if (overlapping_with_target_lanes) { if (!ahead_of_ego && !is_stopped) { trailing_objects.push_back(object); return true; @@ -1247,4 +1245,12 @@ bool filter_target_lane_objects( return false; } + +bool object_path_overlaps_lanes( + const ExtendedPredictedObject & object, const lanelet::BasicPolygon2d & lanes_polygon) +{ + return ranges::any_of(get_line_string_paths(object), [&](const auto & path) { + return !boost::geometry::disjoint(path, lanes_polygon); + }); +} } // namespace autoware::behavior_path_planner::utils::lane_change diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index 5c29f347ad9ef..2ed9fdd9197df 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -71,6 +71,16 @@ bool is_within_circle( const geometry_msgs::msg::Point & object_pos, const geometry_msgs::msg::Point & reference_point, const double search_radius); +/** + * @brief Checks if the object classification represents a vehicle (CAR, TRUCK, BUS, TRAILER, + * MOTORCYCLE). + * + * @param classification The object classification to check. + * @return true If the classification is a vehicle type. + * @return false Otherwise. + */ +bool is_vehicle(const ObjectClassification & classification); + } // namespace autoware::behavior_path_planner::utils::path_safety_checker::filter namespace autoware::behavior_path_planner::utils::path_safety_checker diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp index 1caf287ee5386..00e9a0f567e7c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp @@ -57,6 +57,20 @@ bool is_within_circle( std::hypot(reference_point.x - object_pos.x, reference_point.y - object_pos.y); return dist < search_radius; } + +bool is_vehicle(const ObjectClassification & classification) +{ + switch (classification.label) { + case ObjectClassification::CAR: + case ObjectClassification::TRUCK: + case ObjectClassification::BUS: + case ObjectClassification::TRAILER: + case ObjectClassification::MOTORCYCLE: + return true; + default: + return false; + } +} } // namespace autoware::behavior_path_planner::utils::path_safety_checker::filter namespace autoware::behavior_path_planner::utils::path_safety_checker From ca507d610127e2ade4ae4574fe0c2e3e81837a18 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez <33620+esteve@users.noreply.github.com> Date: Mon, 9 Dec 2024 14:00:11 +0100 Subject: [PATCH 256/273] chore: move rviz plugins from common to visualization/ folder (#9417) Signed-off-by: Esteve Fernandez --- .../CHANGELOG.rst | 0 .../CMakeLists.txt | 0 .../LICENSE | 0 .../README.md | 0 .../assets/av_timer.png | Bin .../assets/font/Quicksand/LICENSE | 0 .../assets/font/Quicksand/static/Quicksand-Bold.ttf | Bin .../font/Quicksand/static/Quicksand-Regular.ttf | Bin .../assets/path.png | Bin ...mission_details_overlay_rviz_plugin-extras.cmake | 0 .../include/mission_details_display.hpp | 0 .../include/overlay_utils.hpp | 0 .../include/remaining_distance_time_display.hpp | 0 .../package.xml | 0 .../plugins_description.xml | 0 .../src/mission_details_display.cpp | 0 .../src/overlay_utils.cpp | 0 .../src/remaining_distance_time_display.cpp | 0 .../autoware_overlay_rviz_plugin/CHANGELOG.rst | 0 .../autoware_overlay_rviz_plugin/CMakeLists.txt | 0 .../autoware_overlay_rviz_plugin/LICENSE | 0 .../autoware_overlay_rviz_plugin/README.md | 0 .../assets/font/Quicksand/LICENSE | 0 .../assets/font/Quicksand/static/Quicksand-Bold.ttf | Bin .../font/Quicksand/static/Quicksand-Light.ttf | Bin .../font/Quicksand/static/Quicksand-Medium.ttf | Bin .../font/Quicksand/static/Quicksand-Regular.ttf | Bin .../font/Quicksand/static/Quicksand-SemiBold.ttf | Bin .../assets/images/arrow.png | Bin .../assets/images/select_add.png | Bin .../assets/images/select_topic_name.png | Bin .../assets/images/traffic.png | Bin .../assets/images/wheel.png | Bin .../autoware_overlay_rviz_plugin-extras.cmake | 0 .../include/gear_display.hpp | 0 .../include/overlay_utils.hpp | 0 .../include/signal_display.hpp | 0 .../include/speed_display.hpp | 0 .../include/speed_limit_display.hpp | 0 .../include/steering_wheel_display.hpp | 0 .../include/traffic_display.hpp | 0 .../include/turn_signals_display.hpp | 0 .../autoware_overlay_rviz_plugin/package.xml | 0 .../plugins_description.xml | 0 .../src/gear_display.cpp | 0 .../src/overlay_utils.cpp | 0 .../src/signal_display.cpp | 0 .../src/speed_display.cpp | 0 .../src/speed_limit_display.cpp | 0 .../src/steering_wheel_display.cpp | 0 .../src/traffic_display.cpp | 0 .../src/turn_signals_display.cpp | 0 .../autoware_perception_rviz_plugin/CHANGELOG.rst | 0 .../autoware_perception_rviz_plugin/CMakeLists.txt | 0 .../autoware_perception_rviz_plugin/README.md | 0 .../icons/classes/DetectedObjects.png | Bin .../icons/classes/PredictedObjects.png | Bin .../icons/classes/TrackedObjects.png | Bin .../detected-object-visualization-description.jpg | Bin .../predicted-object-visualization-description.jpg | Bin .../tracked-object-visualization-description.jpg | Bin .../common/color_alpha_property.hpp | 0 .../object_detection/detected_objects_display.hpp | 0 .../object_detection/object_polygon_detail.hpp | 0 .../object_polygon_display_base.hpp | 0 .../object_detection/predicted_objects_display.hpp | 0 .../object_detection/tracked_objects_display.hpp | 0 .../visibility_control.hpp | 0 .../autoware_perception_rviz_plugin/package.xml | 0 .../plugins_description.xml | 0 .../src/common/color_alpha_property.cpp | 0 .../object_detection/detected_objects_display.cpp | 0 .../src/object_detection/object_polygon_detail.cpp | 0 .../object_detection/predicted_objects_display.cpp | 0 .../object_detection/tracked_objects_display.cpp | 0 .../bag_time_manager_rviz_plugin/CHANGELOG.rst | 0 .../bag_time_manager_rviz_plugin/CMakeLists.txt | 0 .../bag_time_manager_rviz_plugin/README.md | 0 .../icons/classes/BagTimeManagerPanel.png | Bin .../images/add_bag_time_manager_panel.png | Bin .../images/bag_time_manager_panel.png | Bin .../images/select_panels.png | Bin .../bag_time_manager_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/bag_time_manager_panel.cpp | 0 .../src/bag_time_manager_panel.hpp | 0 .../tier4_adapi_rviz_plugin/CHANGELOG.rst | 0 .../tier4_adapi_rviz_plugin/CMakeLists.txt | 0 .../tier4_adapi_rviz_plugin/README.md | 0 .../icons/classes/RoutePanel.png | Bin .../icons/classes/RouteTool.png | Bin .../icons/classes/StatePanel.png | Bin .../tier4_adapi_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../tier4_adapi_rviz_plugin/src/door_panel.cpp | 0 .../tier4_adapi_rviz_plugin/src/door_panel.hpp | 0 .../tier4_adapi_rviz_plugin/src/route_panel.cpp | 0 .../tier4_adapi_rviz_plugin/src/route_panel.hpp | 0 .../tier4_adapi_rviz_plugin/src/route_tool.cpp | 0 .../tier4_adapi_rviz_plugin/src/route_tool.hpp | 0 .../tier4_adapi_rviz_plugin/src/state_panel.cpp | 0 .../tier4_adapi_rviz_plugin/src/state_panel.hpp | 0 .../tier4_camera_view_rviz_plugin/CHANGELOG.rst | 0 .../tier4_camera_view_rviz_plugin/CMakeLists.txt | 0 .../tier4_camera_view_rviz_plugin/README.md | 0 .../icons/classes/BirdEyeViewTool.png | Bin .../icons/classes/ThirdPersonViewTool.png | Bin .../tier4_camera_view_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/bird_eye_view_controller.cpp | 0 .../src/bird_eye_view_controller.hpp | 0 .../src/bird_eye_view_tool.cpp | 0 .../src/bird_eye_view_tool.hpp | 0 .../src/third_person_view_controller.cpp | 0 .../src/third_person_view_controller.hpp | 0 .../src/third_person_view_tool.cpp | 0 .../src/third_person_view_tool.hpp | 0 .../tier4_datetime_rviz_plugin/CHANGELOG.rst | 0 .../tier4_datetime_rviz_plugin/CMakeLists.txt | 0 .../tier4_datetime_rviz_plugin/README.md | 0 .../icons/classes/AutowareDateTimePanel.png | Bin .../images/select_datetime_plugin.png | Bin .../images/select_panels.png | Bin .../tier4_datetime_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/autoware_datetime_panel.cpp | 0 .../src/autoware_datetime_panel.hpp | 0 .../tier4_localization_rviz_plugin/CHANGELOG.rst | 0 .../tier4_localization_rviz_plugin/CMakeLists.txt | 0 .../tier4_localization_rviz_plugin/README.md | 0 .../icons/classes/PoseHistory.png | Bin .../icons/classes/PoseHistoryFootprint.png | Bin .../icons/classes/PoseWithCovarianceHistory.png | Bin .../images/ex_pose_with_covariance_history.png | Bin .../images/select_add.png | Bin .../images/select_localization_plugin.png | Bin .../images/select_topic_name.png | Bin .../tier4_localization_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/pose_history/pose_history_display.cpp | 0 .../src/pose_history/pose_history_display.hpp | 0 .../src/pose_history_footprint/display.cpp | 0 .../src/pose_history_footprint/display.hpp | 0 .../pose_with_covariance_history_display.cpp | 0 .../pose_with_covariance_history_display.hpp | 0 .../tier4_planning_rviz_plugin/CHANGELOG.rst | 0 .../tier4_planning_rviz_plugin/CMakeLists.txt | 0 .../tier4_planning_rviz_plugin/README.md | 0 .../icons/classes/DrivableArea.png | Bin .../icons/classes/MaxVelocity.png | Bin .../icons/classes/MissionCheckpointTool.png | Bin .../icons/classes/Path.png | Bin .../icons/classes/PathFootprint.png | Bin .../icons/classes/PathWithLaneId.png | Bin .../icons/classes/PathWithLaneIdFootprint.png | Bin .../icons/classes/PoseWithUuidStamped.png | Bin .../icons/classes/Trajectory.png | Bin .../icons/classes/TrajectoryFootprint.png | Bin .../images/select_add.png | Bin .../images/select_planning_plugin.png | Bin .../images/select_topic_name.png | Bin .../mission_checkpoint/mission_checkpoint.hpp | 0 .../tier4_planning_rviz_plugin/path/display.hpp | 0 .../path/display_base.hpp | 0 .../pose_with_uuid_stamped/display.hpp | 0 .../include/tier4_planning_rviz_plugin/utils.hpp | 0 .../tier4_planning_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/mission_checkpoint/mission_checkpoint.cpp | 0 .../tier4_planning_rviz_plugin/src/path/display.cpp | 0 .../src/pose_with_uuid_stamped/display.cpp | 0 .../src/tools/jsk_overlay_utils.cpp | 0 .../src/tools/jsk_overlay_utils.hpp | 0 .../src/tools/max_velocity.cpp | 0 .../src/tools/max_velocity.hpp | 0 .../tier4_state_rviz_plugin/CHANGELOG.rst | 0 .../tier4_state_rviz_plugin/CMakeLists.txt | 0 .../tier4_state_rviz_plugin/README.md | 0 .../tier4_state_rviz_plugin/icons/assets/active.png | Bin .../tier4_state_rviz_plugin/icons/assets/crash.png | Bin .../tier4_state_rviz_plugin/icons/assets/danger.png | Bin .../tier4_state_rviz_plugin/icons/assets/none.png | Bin .../icons/assets/pending.png | Bin .../icons/classes/AutowareStatePanel.png | Bin .../icons/classes/VelocitySteeringFactorsPanel.png | Bin .../tier4_state_rviz_plugin/images/select_auto.png | Bin .../images/select_panels.png | Bin .../images/select_state_plugin.png | Bin .../tier4_state_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/autoware_state_panel.cpp | 0 .../tier4_state_rviz_plugin/src/custom_button.cpp | 0 .../src/custom_container.cpp | 0 .../src/custom_icon_label.cpp | 0 .../tier4_state_rviz_plugin/src/custom_label.cpp | 0 .../src/custom_segmented_button.cpp | 0 .../src/custom_segmented_button_item.cpp | 0 .../tier4_state_rviz_plugin/src/custom_slider.cpp | 0 .../src/custom_toggle_switch.cpp | 0 .../src/include/autoware_state_panel.hpp | 0 .../src/include/custom_button.hpp | 0 .../src/include/custom_container.hpp | 0 .../src/include/custom_icon_label.hpp | 0 .../src/include/custom_label.hpp | 0 .../src/include/custom_segmented_button.hpp | 0 .../src/include/custom_segmented_button_item.hpp | 0 .../src/include/custom_slider.hpp | 0 .../src/include/custom_toggle_switch.hpp | 0 .../src/include/material_colors.hpp | 0 .../src/include/velocity_steering_factors_panel.hpp | 0 .../src/velocity_steering_factors_panel.cpp | 0 .../tier4_system_rviz_plugin/CHANGELOG.rst | 0 .../tier4_system_rviz_plugin/CMakeLists.txt | 0 .../tier4_system_rviz_plugin/README.md | 0 .../tier4_system_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/jsk_overlay_utils.cpp | 0 .../src/jsk_overlay_utils.hpp | 0 .../src/mrm_summary_overlay_display.cpp | 0 .../src/mrm_summary_overlay_display.hpp | 0 .../tier4_traffic_light_rviz_plugin/CHANGELOG.rst | 0 .../tier4_traffic_light_rviz_plugin/CMakeLists.txt | 0 .../tier4_traffic_light_rviz_plugin/README.md | 0 .../icons/classes/TrafficLightPublishPanel.png | Bin .../images/select_panels.png | Bin .../images/select_traffic_light_id.png | Bin .../images/select_traffic_light_publish_panel.png | Bin .../images/traffic_light_publish_panel.gif | Bin .../tier4_traffic_light_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/traffic_light_publish_panel.cpp | 0 .../src/traffic_light_publish_panel.hpp | 0 .../tier4_vehicle_rviz_plugin/CHANGELOG.rst | 0 .../tier4_vehicle_rviz_plugin/CMakeLists.txt | 0 .../tier4_vehicle_rviz_plugin/README.md | 0 .../icons/classes/AccelerationMeter.png | Bin .../icons/classes/ConsoleMeter.png | Bin .../icons/classes/SteeringAngle.png | Bin .../icons/classes/TurnSignal.png | Bin .../icons/classes/VelocityHistory.png | Bin .../tier4_vehicle_rviz_plugin/images/handle.png | Bin .../tier4_vehicle_rviz_plugin/images/select_add.png | Bin .../images/select_topic_name.png | Bin .../images/select_vehicle_plugin.png | Bin .../tier4_vehicle_rviz_plugin/package.xml | 0 .../plugins/plugin_description.xml | 0 .../src/tools/acceleration_meter.cpp | 0 .../src/tools/acceleration_meter.hpp | 0 .../src/tools/console_meter.cpp | 0 .../src/tools/console_meter.hpp | 0 .../src/tools/jsk_overlay_utils.cpp | 0 .../src/tools/jsk_overlay_utils.hpp | 0 .../src/tools/steering_angle.cpp | 0 .../src/tools/steering_angle.hpp | 0 .../src/tools/turn_signal.cpp | 0 .../src/tools/turn_signal.hpp | 0 .../src/tools/velocity_history.cpp | 0 .../src/tools/velocity_history.hpp | 0 258 files changed, 0 insertions(+), 0 deletions(-) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/LICENSE (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/LICENSE (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-SemiBold.ttf (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/arrow.png (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_add.png (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_topic_name.png (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/traffic.png (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/wheel.png (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin-extras.cmake (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/gear_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/steering_wheel_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/plugins_description.xml (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp (100%) rename {common => visualization}/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/autoware_perception_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/autoware_perception_rviz_plugin/README.md (100%) rename {common => visualization}/autoware_perception_rviz_plugin/icons/classes/DetectedObjects.png (100%) rename {common => visualization}/autoware_perception_rviz_plugin/icons/classes/PredictedObjects.png (100%) rename {common => visualization}/autoware_perception_rviz_plugin/icons/classes/TrackedObjects.png (100%) rename {common => visualization}/autoware_perception_rviz_plugin/images/detected-object-visualization-description.jpg (100%) rename {common => visualization}/autoware_perception_rviz_plugin/images/predicted-object-visualization-description.jpg (100%) rename {common => visualization}/autoware_perception_rviz_plugin/images/tracked-object-visualization-description.jpg (100%) rename {common => visualization}/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/common/color_alpha_property.hpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/detected_objects_display.hpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/predicted_objects_display.hpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/tracked_objects_display.hpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/visibility_control.hpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/package.xml (100%) rename {common => visualization}/autoware_perception_rviz_plugin/plugins_description.xml (100%) rename {common => visualization}/autoware_perception_rviz_plugin/src/common/color_alpha_property.cpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp (100%) rename {common => visualization}/autoware_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/README.md (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/images/select_panels.png (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/package.xml (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp (100%) rename {common => visualization}/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/icons/classes/RoutePanel.png (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/icons/classes/RouteTool.png (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/icons/classes/StatePanel.png (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/src/door_panel.cpp (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/src/door_panel.hpp (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/src/route_panel.cpp (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/src/route_panel.hpp (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/src/route_tool.cpp (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/src/route_tool.hpp (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/src/state_panel.cpp (100%) rename {common => visualization}/tier4_adapi_rviz_plugin/src/state_panel.hpp (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/icons/classes/BirdEyeViewTool.png (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/icons/classes/ThirdPersonViewTool.png (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp (100%) rename {common => visualization}/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/icons/classes/AutowareDateTimePanel.png (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/images/select_datetime_plugin.png (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/images/select_panels.png (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.cpp (100%) rename {common => visualization}/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.hpp (100%) rename {common => visualization}/tier4_localization_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_localization_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_localization_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_localization_rviz_plugin/icons/classes/PoseHistory.png (100%) rename {common => visualization}/tier4_localization_rviz_plugin/icons/classes/PoseHistoryFootprint.png (100%) rename {common => visualization}/tier4_localization_rviz_plugin/icons/classes/PoseWithCovarianceHistory.png (100%) rename {common => visualization}/tier4_localization_rviz_plugin/images/ex_pose_with_covariance_history.png (100%) rename {common => visualization}/tier4_localization_rviz_plugin/images/select_add.png (100%) rename {common => visualization}/tier4_localization_rviz_plugin/images/select_localization_plugin.png (100%) rename {common => visualization}/tier4_localization_rviz_plugin/images/select_topic_name.png (100%) rename {common => visualization}/tier4_localization_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_localization_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp (100%) rename {common => visualization}/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp (100%) rename {common => visualization}/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp (100%) rename {common => visualization}/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp (100%) rename {common => visualization}/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp (100%) rename {common => visualization}/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_planning_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_planning_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/DrivableArea.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/MaxVelocity.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/MissionCheckpointTool.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/Path.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/PathFootprint.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/PathWithLaneId.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/PathWithLaneIdFootprint.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/PoseWithUuidStamped.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/Trajectory.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/icons/classes/TrajectoryFootprint.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/images/select_add.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/images/select_planning_plugin.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/images/select_topic_name.png (100%) rename {common => visualization}/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_planning_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/src/path/display.cpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp (100%) rename {common => visualization}/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_state_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_state_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_state_rviz_plugin/icons/assets/active.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/icons/assets/crash.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/icons/assets/danger.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/icons/assets/none.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/icons/assets/pending.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/icons/classes/AutowareStatePanel.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/icons/classes/VelocitySteeringFactorsPanel.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/images/select_auto.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/images/select_panels.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/images/select_state_plugin.png (100%) rename {common => visualization}/tier4_state_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_state_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/autoware_state_panel.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/custom_button.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/custom_container.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/custom_icon_label.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/custom_label.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/custom_segmented_button.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/custom_slider.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/custom_button.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/custom_container.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/custom_icon_label.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/custom_label.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/custom_segmented_button.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/custom_slider.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/custom_toggle_switch.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/material_colors.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp (100%) rename {common => visualization}/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp (100%) rename {common => visualization}/tier4_system_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_system_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_system_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_system_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_system_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_system_rviz_plugin/src/jsk_overlay_utils.cpp (100%) rename {common => visualization}/tier4_system_rviz_plugin/src/jsk_overlay_utils.hpp (100%) rename {common => visualization}/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp (100%) rename {common => visualization}/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.hpp (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/icons/classes/TrafficLightPublishPanel.png (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/images/select_panels.png (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/images/select_traffic_light_id.png (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/images/select_traffic_light_publish_panel.png (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp (100%) rename {common => visualization}/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/CHANGELOG.rst (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/CMakeLists.txt (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/README.md (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/icons/classes/AccelerationMeter.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/icons/classes/ConsoleMeter.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/icons/classes/SteeringAngle.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/icons/classes/TurnSignal.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/icons/classes/VelocityHistory.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/images/handle.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/images/select_add.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/images/select_topic_name.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/images/select_vehicle_plugin.png (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/package.xml (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.cpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.hpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/steering_angle.hpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/turn_signal.cpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/turn_signal.hpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/velocity_history.cpp (100%) rename {common => visualization}/tier4_vehicle_rviz_plugin/src/tools/velocity_history.hpp (100%) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CMakeLists.txt diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/LICENSE b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/LICENSE similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/LICENSE rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/LICENSE diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/README.md diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/LICENSE b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/LICENSE similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/LICENSE rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/LICENSE diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Light.ttf diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Medium.ttf diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-SemiBold.ttf b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-SemiBold.ttf similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-SemiBold.ttf rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-SemiBold.ttf diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/arrow.png b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/arrow.png similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/arrow.png rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/arrow.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_add.png b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_add.png similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_add.png rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_add.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_topic_name.png b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_topic_name.png similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_topic_name.png rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/select_topic_name.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/traffic.png b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/traffic.png similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/traffic.png rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/traffic.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/wheel.png b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/wheel.png similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/wheel.png rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/assets/images/wheel.png diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin-extras.cmake b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin-extras.cmake similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin-extras.cmake rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin-extras.cmake diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/gear_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/gear_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/gear_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/gear_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/overlay_utils.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/signal_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/speed_limit_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/steering_wheel_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/steering_wheel_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/steering_wheel_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/steering_wheel_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/traffic_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/include/turn_signals_display.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/plugins_description.xml b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/plugins_description.xml similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/plugins_description.xml rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/plugins_description.xml diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/gear_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/overlay_utils.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/signal_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/speed_limit_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/steering_wheel_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/traffic_display.cpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp similarity index 100% rename from common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp rename to visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/src/turn_signals_display.cpp diff --git a/common/autoware_perception_rviz_plugin/CHANGELOG.rst b/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/autoware_perception_rviz_plugin/CHANGELOG.rst rename to visualization/autoware_perception_rviz_plugin/CHANGELOG.rst diff --git a/common/autoware_perception_rviz_plugin/CMakeLists.txt b/visualization/autoware_perception_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/autoware_perception_rviz_plugin/CMakeLists.txt rename to visualization/autoware_perception_rviz_plugin/CMakeLists.txt diff --git a/common/autoware_perception_rviz_plugin/README.md b/visualization/autoware_perception_rviz_plugin/README.md similarity index 100% rename from common/autoware_perception_rviz_plugin/README.md rename to visualization/autoware_perception_rviz_plugin/README.md diff --git a/common/autoware_perception_rviz_plugin/icons/classes/DetectedObjects.png b/visualization/autoware_perception_rviz_plugin/icons/classes/DetectedObjects.png similarity index 100% rename from common/autoware_perception_rviz_plugin/icons/classes/DetectedObjects.png rename to visualization/autoware_perception_rviz_plugin/icons/classes/DetectedObjects.png diff --git a/common/autoware_perception_rviz_plugin/icons/classes/PredictedObjects.png b/visualization/autoware_perception_rviz_plugin/icons/classes/PredictedObjects.png similarity index 100% rename from common/autoware_perception_rviz_plugin/icons/classes/PredictedObjects.png rename to visualization/autoware_perception_rviz_plugin/icons/classes/PredictedObjects.png diff --git a/common/autoware_perception_rviz_plugin/icons/classes/TrackedObjects.png b/visualization/autoware_perception_rviz_plugin/icons/classes/TrackedObjects.png similarity index 100% rename from common/autoware_perception_rviz_plugin/icons/classes/TrackedObjects.png rename to visualization/autoware_perception_rviz_plugin/icons/classes/TrackedObjects.png diff --git a/common/autoware_perception_rviz_plugin/images/detected-object-visualization-description.jpg b/visualization/autoware_perception_rviz_plugin/images/detected-object-visualization-description.jpg similarity index 100% rename from common/autoware_perception_rviz_plugin/images/detected-object-visualization-description.jpg rename to visualization/autoware_perception_rviz_plugin/images/detected-object-visualization-description.jpg diff --git a/common/autoware_perception_rviz_plugin/images/predicted-object-visualization-description.jpg b/visualization/autoware_perception_rviz_plugin/images/predicted-object-visualization-description.jpg similarity index 100% rename from common/autoware_perception_rviz_plugin/images/predicted-object-visualization-description.jpg rename to visualization/autoware_perception_rviz_plugin/images/predicted-object-visualization-description.jpg diff --git a/common/autoware_perception_rviz_plugin/images/tracked-object-visualization-description.jpg b/visualization/autoware_perception_rviz_plugin/images/tracked-object-visualization-description.jpg similarity index 100% rename from common/autoware_perception_rviz_plugin/images/tracked-object-visualization-description.jpg rename to visualization/autoware_perception_rviz_plugin/images/tracked-object-visualization-description.jpg diff --git a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/common/color_alpha_property.hpp b/visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/common/color_alpha_property.hpp similarity index 100% rename from common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/common/color_alpha_property.hpp rename to visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/common/color_alpha_property.hpp diff --git a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/detected_objects_display.hpp b/visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/detected_objects_display.hpp similarity index 100% rename from common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/detected_objects_display.hpp rename to visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/detected_objects_display.hpp diff --git a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp b/visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp similarity index 100% rename from common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp rename to visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_detail.hpp diff --git a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp b/visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp similarity index 100% rename from common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp rename to visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/object_polygon_display_base.hpp diff --git a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/predicted_objects_display.hpp b/visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/predicted_objects_display.hpp similarity index 100% rename from common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/predicted_objects_display.hpp rename to visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/predicted_objects_display.hpp diff --git a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/tracked_objects_display.hpp b/visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/tracked_objects_display.hpp similarity index 100% rename from common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/tracked_objects_display.hpp rename to visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/object_detection/tracked_objects_display.hpp diff --git a/common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/visibility_control.hpp b/visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/visibility_control.hpp similarity index 100% rename from common/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/visibility_control.hpp rename to visualization/autoware_perception_rviz_plugin/include/autoware_perception_rviz_plugin/visibility_control.hpp diff --git a/common/autoware_perception_rviz_plugin/package.xml b/visualization/autoware_perception_rviz_plugin/package.xml similarity index 100% rename from common/autoware_perception_rviz_plugin/package.xml rename to visualization/autoware_perception_rviz_plugin/package.xml diff --git a/common/autoware_perception_rviz_plugin/plugins_description.xml b/visualization/autoware_perception_rviz_plugin/plugins_description.xml similarity index 100% rename from common/autoware_perception_rviz_plugin/plugins_description.xml rename to visualization/autoware_perception_rviz_plugin/plugins_description.xml diff --git a/common/autoware_perception_rviz_plugin/src/common/color_alpha_property.cpp b/visualization/autoware_perception_rviz_plugin/src/common/color_alpha_property.cpp similarity index 100% rename from common/autoware_perception_rviz_plugin/src/common/color_alpha_property.cpp rename to visualization/autoware_perception_rviz_plugin/src/common/color_alpha_property.cpp diff --git a/common/autoware_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp b/visualization/autoware_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp similarity index 100% rename from common/autoware_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp rename to visualization/autoware_perception_rviz_plugin/src/object_detection/detected_objects_display.cpp diff --git a/common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp b/visualization/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp similarity index 100% rename from common/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp rename to visualization/autoware_perception_rviz_plugin/src/object_detection/object_polygon_detail.cpp diff --git a/common/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp b/visualization/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp similarity index 100% rename from common/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp rename to visualization/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp diff --git a/common/autoware_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp b/visualization/autoware_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp similarity index 100% rename from common/autoware_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp rename to visualization/autoware_perception_rviz_plugin/src/object_detection/tracked_objects_display.cpp diff --git a/common/bag_time_manager_rviz_plugin/CHANGELOG.rst b/visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/bag_time_manager_rviz_plugin/CHANGELOG.rst rename to visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst diff --git a/common/bag_time_manager_rviz_plugin/CMakeLists.txt b/visualization/bag_time_manager_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/bag_time_manager_rviz_plugin/CMakeLists.txt rename to visualization/bag_time_manager_rviz_plugin/CMakeLists.txt diff --git a/common/bag_time_manager_rviz_plugin/README.md b/visualization/bag_time_manager_rviz_plugin/README.md similarity index 100% rename from common/bag_time_manager_rviz_plugin/README.md rename to visualization/bag_time_manager_rviz_plugin/README.md diff --git a/common/bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png b/visualization/bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png similarity index 100% rename from common/bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png rename to visualization/bag_time_manager_rviz_plugin/icons/classes/BagTimeManagerPanel.png diff --git a/common/bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png b/visualization/bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png similarity index 100% rename from common/bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png rename to visualization/bag_time_manager_rviz_plugin/images/add_bag_time_manager_panel.png diff --git a/common/bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png b/visualization/bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png similarity index 100% rename from common/bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png rename to visualization/bag_time_manager_rviz_plugin/images/bag_time_manager_panel.png diff --git a/common/bag_time_manager_rviz_plugin/images/select_panels.png b/visualization/bag_time_manager_rviz_plugin/images/select_panels.png similarity index 100% rename from common/bag_time_manager_rviz_plugin/images/select_panels.png rename to visualization/bag_time_manager_rviz_plugin/images/select_panels.png diff --git a/common/bag_time_manager_rviz_plugin/package.xml b/visualization/bag_time_manager_rviz_plugin/package.xml similarity index 100% rename from common/bag_time_manager_rviz_plugin/package.xml rename to visualization/bag_time_manager_rviz_plugin/package.xml diff --git a/common/bag_time_manager_rviz_plugin/plugins/plugin_description.xml b/visualization/bag_time_manager_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/bag_time_manager_rviz_plugin/plugins/plugin_description.xml rename to visualization/bag_time_manager_rviz_plugin/plugins/plugin_description.xml diff --git a/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp b/visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp similarity index 100% rename from common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp rename to visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp diff --git a/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp b/visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp similarity index 100% rename from common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp rename to visualization/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.hpp diff --git a/common/tier4_adapi_rviz_plugin/CHANGELOG.rst b/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_adapi_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_adapi_rviz_plugin/CMakeLists.txt b/visualization/tier4_adapi_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_adapi_rviz_plugin/CMakeLists.txt rename to visualization/tier4_adapi_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_adapi_rviz_plugin/README.md b/visualization/tier4_adapi_rviz_plugin/README.md similarity index 100% rename from common/tier4_adapi_rviz_plugin/README.md rename to visualization/tier4_adapi_rviz_plugin/README.md diff --git a/common/tier4_adapi_rviz_plugin/icons/classes/RoutePanel.png b/visualization/tier4_adapi_rviz_plugin/icons/classes/RoutePanel.png similarity index 100% rename from common/tier4_adapi_rviz_plugin/icons/classes/RoutePanel.png rename to visualization/tier4_adapi_rviz_plugin/icons/classes/RoutePanel.png diff --git a/common/tier4_adapi_rviz_plugin/icons/classes/RouteTool.png b/visualization/tier4_adapi_rviz_plugin/icons/classes/RouteTool.png similarity index 100% rename from common/tier4_adapi_rviz_plugin/icons/classes/RouteTool.png rename to visualization/tier4_adapi_rviz_plugin/icons/classes/RouteTool.png diff --git a/common/tier4_adapi_rviz_plugin/icons/classes/StatePanel.png b/visualization/tier4_adapi_rviz_plugin/icons/classes/StatePanel.png similarity index 100% rename from common/tier4_adapi_rviz_plugin/icons/classes/StatePanel.png rename to visualization/tier4_adapi_rviz_plugin/icons/classes/StatePanel.png diff --git a/common/tier4_adapi_rviz_plugin/package.xml b/visualization/tier4_adapi_rviz_plugin/package.xml similarity index 100% rename from common/tier4_adapi_rviz_plugin/package.xml rename to visualization/tier4_adapi_rviz_plugin/package.xml diff --git a/common/tier4_adapi_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_adapi_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_adapi_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_adapi_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_adapi_rviz_plugin/src/door_panel.cpp b/visualization/tier4_adapi_rviz_plugin/src/door_panel.cpp similarity index 100% rename from common/tier4_adapi_rviz_plugin/src/door_panel.cpp rename to visualization/tier4_adapi_rviz_plugin/src/door_panel.cpp diff --git a/common/tier4_adapi_rviz_plugin/src/door_panel.hpp b/visualization/tier4_adapi_rviz_plugin/src/door_panel.hpp similarity index 100% rename from common/tier4_adapi_rviz_plugin/src/door_panel.hpp rename to visualization/tier4_adapi_rviz_plugin/src/door_panel.hpp diff --git a/common/tier4_adapi_rviz_plugin/src/route_panel.cpp b/visualization/tier4_adapi_rviz_plugin/src/route_panel.cpp similarity index 100% rename from common/tier4_adapi_rviz_plugin/src/route_panel.cpp rename to visualization/tier4_adapi_rviz_plugin/src/route_panel.cpp diff --git a/common/tier4_adapi_rviz_plugin/src/route_panel.hpp b/visualization/tier4_adapi_rviz_plugin/src/route_panel.hpp similarity index 100% rename from common/tier4_adapi_rviz_plugin/src/route_panel.hpp rename to visualization/tier4_adapi_rviz_plugin/src/route_panel.hpp diff --git a/common/tier4_adapi_rviz_plugin/src/route_tool.cpp b/visualization/tier4_adapi_rviz_plugin/src/route_tool.cpp similarity index 100% rename from common/tier4_adapi_rviz_plugin/src/route_tool.cpp rename to visualization/tier4_adapi_rviz_plugin/src/route_tool.cpp diff --git a/common/tier4_adapi_rviz_plugin/src/route_tool.hpp b/visualization/tier4_adapi_rviz_plugin/src/route_tool.hpp similarity index 100% rename from common/tier4_adapi_rviz_plugin/src/route_tool.hpp rename to visualization/tier4_adapi_rviz_plugin/src/route_tool.hpp diff --git a/common/tier4_adapi_rviz_plugin/src/state_panel.cpp b/visualization/tier4_adapi_rviz_plugin/src/state_panel.cpp similarity index 100% rename from common/tier4_adapi_rviz_plugin/src/state_panel.cpp rename to visualization/tier4_adapi_rviz_plugin/src/state_panel.cpp diff --git a/common/tier4_adapi_rviz_plugin/src/state_panel.hpp b/visualization/tier4_adapi_rviz_plugin/src/state_panel.hpp similarity index 100% rename from common/tier4_adapi_rviz_plugin/src/state_panel.hpp rename to visualization/tier4_adapi_rviz_plugin/src/state_panel.hpp diff --git a/common/tier4_camera_view_rviz_plugin/CHANGELOG.rst b/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_camera_view_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_camera_view_rviz_plugin/CMakeLists.txt b/visualization/tier4_camera_view_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_camera_view_rviz_plugin/CMakeLists.txt rename to visualization/tier4_camera_view_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_camera_view_rviz_plugin/README.md b/visualization/tier4_camera_view_rviz_plugin/README.md similarity index 100% rename from common/tier4_camera_view_rviz_plugin/README.md rename to visualization/tier4_camera_view_rviz_plugin/README.md diff --git a/common/tier4_camera_view_rviz_plugin/icons/classes/BirdEyeViewTool.png b/visualization/tier4_camera_view_rviz_plugin/icons/classes/BirdEyeViewTool.png similarity index 100% rename from common/tier4_camera_view_rviz_plugin/icons/classes/BirdEyeViewTool.png rename to visualization/tier4_camera_view_rviz_plugin/icons/classes/BirdEyeViewTool.png diff --git a/common/tier4_camera_view_rviz_plugin/icons/classes/ThirdPersonViewTool.png b/visualization/tier4_camera_view_rviz_plugin/icons/classes/ThirdPersonViewTool.png similarity index 100% rename from common/tier4_camera_view_rviz_plugin/icons/classes/ThirdPersonViewTool.png rename to visualization/tier4_camera_view_rviz_plugin/icons/classes/ThirdPersonViewTool.png diff --git a/common/tier4_camera_view_rviz_plugin/package.xml b/visualization/tier4_camera_view_rviz_plugin/package.xml similarity index 100% rename from common/tier4_camera_view_rviz_plugin/package.xml rename to visualization/tier4_camera_view_rviz_plugin/package.xml diff --git a/common/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_camera_view_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp b/visualization/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp similarity index 100% rename from common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp rename to visualization/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.cpp diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp b/visualization/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp similarity index 100% rename from common/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp rename to visualization/tier4_camera_view_rviz_plugin/src/bird_eye_view_controller.hpp diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp b/visualization/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp similarity index 100% rename from common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp rename to visualization/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.cpp diff --git a/common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp b/visualization/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp similarity index 100% rename from common/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp rename to visualization/tier4_camera_view_rviz_plugin/src/bird_eye_view_tool.hpp diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp b/visualization/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp similarity index 100% rename from common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp rename to visualization/tier4_camera_view_rviz_plugin/src/third_person_view_controller.cpp diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp b/visualization/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp similarity index 100% rename from common/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp rename to visualization/tier4_camera_view_rviz_plugin/src/third_person_view_controller.hpp diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp b/visualization/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp similarity index 100% rename from common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp rename to visualization/tier4_camera_view_rviz_plugin/src/third_person_view_tool.cpp diff --git a/common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp b/visualization/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp similarity index 100% rename from common/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp rename to visualization/tier4_camera_view_rviz_plugin/src/third_person_view_tool.hpp diff --git a/common/tier4_datetime_rviz_plugin/CHANGELOG.rst b/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_datetime_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_datetime_rviz_plugin/CMakeLists.txt b/visualization/tier4_datetime_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_datetime_rviz_plugin/CMakeLists.txt rename to visualization/tier4_datetime_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_datetime_rviz_plugin/README.md b/visualization/tier4_datetime_rviz_plugin/README.md similarity index 100% rename from common/tier4_datetime_rviz_plugin/README.md rename to visualization/tier4_datetime_rviz_plugin/README.md diff --git a/common/tier4_datetime_rviz_plugin/icons/classes/AutowareDateTimePanel.png b/visualization/tier4_datetime_rviz_plugin/icons/classes/AutowareDateTimePanel.png similarity index 100% rename from common/tier4_datetime_rviz_plugin/icons/classes/AutowareDateTimePanel.png rename to visualization/tier4_datetime_rviz_plugin/icons/classes/AutowareDateTimePanel.png diff --git a/common/tier4_datetime_rviz_plugin/images/select_datetime_plugin.png b/visualization/tier4_datetime_rviz_plugin/images/select_datetime_plugin.png similarity index 100% rename from common/tier4_datetime_rviz_plugin/images/select_datetime_plugin.png rename to visualization/tier4_datetime_rviz_plugin/images/select_datetime_plugin.png diff --git a/common/tier4_datetime_rviz_plugin/images/select_panels.png b/visualization/tier4_datetime_rviz_plugin/images/select_panels.png similarity index 100% rename from common/tier4_datetime_rviz_plugin/images/select_panels.png rename to visualization/tier4_datetime_rviz_plugin/images/select_panels.png diff --git a/common/tier4_datetime_rviz_plugin/package.xml b/visualization/tier4_datetime_rviz_plugin/package.xml similarity index 100% rename from common/tier4_datetime_rviz_plugin/package.xml rename to visualization/tier4_datetime_rviz_plugin/package.xml diff --git a/common/tier4_datetime_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_datetime_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_datetime_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_datetime_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.cpp b/visualization/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.cpp similarity index 100% rename from common/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.cpp rename to visualization/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.cpp diff --git a/common/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.hpp b/visualization/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.hpp similarity index 100% rename from common/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.hpp rename to visualization/tier4_datetime_rviz_plugin/src/autoware_datetime_panel.hpp diff --git a/common/tier4_localization_rviz_plugin/CHANGELOG.rst b/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_localization_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_localization_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_localization_rviz_plugin/CMakeLists.txt b/visualization/tier4_localization_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_localization_rviz_plugin/CMakeLists.txt rename to visualization/tier4_localization_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_localization_rviz_plugin/README.md b/visualization/tier4_localization_rviz_plugin/README.md similarity index 100% rename from common/tier4_localization_rviz_plugin/README.md rename to visualization/tier4_localization_rviz_plugin/README.md diff --git a/common/tier4_localization_rviz_plugin/icons/classes/PoseHistory.png b/visualization/tier4_localization_rviz_plugin/icons/classes/PoseHistory.png similarity index 100% rename from common/tier4_localization_rviz_plugin/icons/classes/PoseHistory.png rename to visualization/tier4_localization_rviz_plugin/icons/classes/PoseHistory.png diff --git a/common/tier4_localization_rviz_plugin/icons/classes/PoseHistoryFootprint.png b/visualization/tier4_localization_rviz_plugin/icons/classes/PoseHistoryFootprint.png similarity index 100% rename from common/tier4_localization_rviz_plugin/icons/classes/PoseHistoryFootprint.png rename to visualization/tier4_localization_rviz_plugin/icons/classes/PoseHistoryFootprint.png diff --git a/common/tier4_localization_rviz_plugin/icons/classes/PoseWithCovarianceHistory.png b/visualization/tier4_localization_rviz_plugin/icons/classes/PoseWithCovarianceHistory.png similarity index 100% rename from common/tier4_localization_rviz_plugin/icons/classes/PoseWithCovarianceHistory.png rename to visualization/tier4_localization_rviz_plugin/icons/classes/PoseWithCovarianceHistory.png diff --git a/common/tier4_localization_rviz_plugin/images/ex_pose_with_covariance_history.png b/visualization/tier4_localization_rviz_plugin/images/ex_pose_with_covariance_history.png similarity index 100% rename from common/tier4_localization_rviz_plugin/images/ex_pose_with_covariance_history.png rename to visualization/tier4_localization_rviz_plugin/images/ex_pose_with_covariance_history.png diff --git a/common/tier4_localization_rviz_plugin/images/select_add.png b/visualization/tier4_localization_rviz_plugin/images/select_add.png similarity index 100% rename from common/tier4_localization_rviz_plugin/images/select_add.png rename to visualization/tier4_localization_rviz_plugin/images/select_add.png diff --git a/common/tier4_localization_rviz_plugin/images/select_localization_plugin.png b/visualization/tier4_localization_rviz_plugin/images/select_localization_plugin.png similarity index 100% rename from common/tier4_localization_rviz_plugin/images/select_localization_plugin.png rename to visualization/tier4_localization_rviz_plugin/images/select_localization_plugin.png diff --git a/common/tier4_localization_rviz_plugin/images/select_topic_name.png b/visualization/tier4_localization_rviz_plugin/images/select_topic_name.png similarity index 100% rename from common/tier4_localization_rviz_plugin/images/select_topic_name.png rename to visualization/tier4_localization_rviz_plugin/images/select_topic_name.png diff --git a/common/tier4_localization_rviz_plugin/package.xml b/visualization/tier4_localization_rviz_plugin/package.xml similarity index 100% rename from common/tier4_localization_rviz_plugin/package.xml rename to visualization/tier4_localization_rviz_plugin/package.xml diff --git a/common/tier4_localization_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_localization_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_localization_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_localization_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp b/visualization/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp similarity index 100% rename from common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp rename to visualization/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.cpp diff --git a/common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp b/visualization/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp similarity index 100% rename from common/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp rename to visualization/tier4_localization_rviz_plugin/src/pose_history/pose_history_display.hpp diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp b/visualization/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp similarity index 100% rename from common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp rename to visualization/tier4_localization_rviz_plugin/src/pose_history_footprint/display.cpp diff --git a/common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp b/visualization/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp similarity index 100% rename from common/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp rename to visualization/tier4_localization_rviz_plugin/src/pose_history_footprint/display.hpp diff --git a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp b/visualization/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp similarity index 100% rename from common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp rename to visualization/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.cpp diff --git a/common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp b/visualization/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp similarity index 100% rename from common/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp rename to visualization/tier4_localization_rviz_plugin/src/pose_with_covariance_history/pose_with_covariance_history_display.hpp diff --git a/common/tier4_planning_rviz_plugin/CHANGELOG.rst b/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_planning_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_planning_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_planning_rviz_plugin/CMakeLists.txt b/visualization/tier4_planning_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_planning_rviz_plugin/CMakeLists.txt rename to visualization/tier4_planning_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_planning_rviz_plugin/README.md b/visualization/tier4_planning_rviz_plugin/README.md similarity index 100% rename from common/tier4_planning_rviz_plugin/README.md rename to visualization/tier4_planning_rviz_plugin/README.md diff --git a/common/tier4_planning_rviz_plugin/icons/classes/DrivableArea.png b/visualization/tier4_planning_rviz_plugin/icons/classes/DrivableArea.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/DrivableArea.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/DrivableArea.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/MaxVelocity.png b/visualization/tier4_planning_rviz_plugin/icons/classes/MaxVelocity.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/MaxVelocity.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/MaxVelocity.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/MissionCheckpointTool.png b/visualization/tier4_planning_rviz_plugin/icons/classes/MissionCheckpointTool.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/MissionCheckpointTool.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/MissionCheckpointTool.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/Path.png b/visualization/tier4_planning_rviz_plugin/icons/classes/Path.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/Path.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/Path.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/PathFootprint.png b/visualization/tier4_planning_rviz_plugin/icons/classes/PathFootprint.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/PathFootprint.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/PathFootprint.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/PathWithLaneId.png b/visualization/tier4_planning_rviz_plugin/icons/classes/PathWithLaneId.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/PathWithLaneId.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/PathWithLaneId.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/PathWithLaneIdFootprint.png b/visualization/tier4_planning_rviz_plugin/icons/classes/PathWithLaneIdFootprint.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/PathWithLaneIdFootprint.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/PathWithLaneIdFootprint.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/PoseWithUuidStamped.png b/visualization/tier4_planning_rviz_plugin/icons/classes/PoseWithUuidStamped.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/PoseWithUuidStamped.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/PoseWithUuidStamped.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/Trajectory.png b/visualization/tier4_planning_rviz_plugin/icons/classes/Trajectory.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/Trajectory.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/Trajectory.png diff --git a/common/tier4_planning_rviz_plugin/icons/classes/TrajectoryFootprint.png b/visualization/tier4_planning_rviz_plugin/icons/classes/TrajectoryFootprint.png similarity index 100% rename from common/tier4_planning_rviz_plugin/icons/classes/TrajectoryFootprint.png rename to visualization/tier4_planning_rviz_plugin/icons/classes/TrajectoryFootprint.png diff --git a/common/tier4_planning_rviz_plugin/images/select_add.png b/visualization/tier4_planning_rviz_plugin/images/select_add.png similarity index 100% rename from common/tier4_planning_rviz_plugin/images/select_add.png rename to visualization/tier4_planning_rviz_plugin/images/select_add.png diff --git a/common/tier4_planning_rviz_plugin/images/select_planning_plugin.png b/visualization/tier4_planning_rviz_plugin/images/select_planning_plugin.png similarity index 100% rename from common/tier4_planning_rviz_plugin/images/select_planning_plugin.png rename to visualization/tier4_planning_rviz_plugin/images/select_planning_plugin.png diff --git a/common/tier4_planning_rviz_plugin/images/select_topic_name.png b/visualization/tier4_planning_rviz_plugin/images/select_topic_name.png similarity index 100% rename from common/tier4_planning_rviz_plugin/images/select_topic_name.png rename to visualization/tier4_planning_rviz_plugin/images/select_topic_name.png diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp b/visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp similarity index 100% rename from common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp rename to visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/mission_checkpoint/mission_checkpoint.hpp diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp b/visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp similarity index 100% rename from common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp rename to visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display.hpp diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp b/visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp similarity index 100% rename from common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp rename to visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/path/display_base.hpp diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp b/visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp similarity index 100% rename from common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp rename to visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/pose_with_uuid_stamped/display.hpp diff --git a/common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp b/visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp similarity index 100% rename from common/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp rename to visualization/tier4_planning_rviz_plugin/include/tier4_planning_rviz_plugin/utils.hpp diff --git a/common/tier4_planning_rviz_plugin/package.xml b/visualization/tier4_planning_rviz_plugin/package.xml similarity index 100% rename from common/tier4_planning_rviz_plugin/package.xml rename to visualization/tier4_planning_rviz_plugin/package.xml diff --git a/common/tier4_planning_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_planning_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_planning_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_planning_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp b/visualization/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp similarity index 100% rename from common/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp rename to visualization/tier4_planning_rviz_plugin/src/mission_checkpoint/mission_checkpoint.cpp diff --git a/common/tier4_planning_rviz_plugin/src/path/display.cpp b/visualization/tier4_planning_rviz_plugin/src/path/display.cpp similarity index 100% rename from common/tier4_planning_rviz_plugin/src/path/display.cpp rename to visualization/tier4_planning_rviz_plugin/src/path/display.cpp diff --git a/common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp b/visualization/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp similarity index 100% rename from common/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp rename to visualization/tier4_planning_rviz_plugin/src/pose_with_uuid_stamped/display.cpp diff --git a/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp b/visualization/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp similarity index 100% rename from common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp rename to visualization/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.cpp diff --git a/common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp b/visualization/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp similarity index 100% rename from common/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp rename to visualization/tier4_planning_rviz_plugin/src/tools/jsk_overlay_utils.hpp diff --git a/common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp b/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp similarity index 100% rename from common/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp rename to visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.cpp diff --git a/common/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp b/visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp similarity index 100% rename from common/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp rename to visualization/tier4_planning_rviz_plugin/src/tools/max_velocity.hpp diff --git a/common/tier4_state_rviz_plugin/CHANGELOG.rst b/visualization/tier4_state_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_state_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_state_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_state_rviz_plugin/CMakeLists.txt b/visualization/tier4_state_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_state_rviz_plugin/CMakeLists.txt rename to visualization/tier4_state_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_state_rviz_plugin/README.md b/visualization/tier4_state_rviz_plugin/README.md similarity index 100% rename from common/tier4_state_rviz_plugin/README.md rename to visualization/tier4_state_rviz_plugin/README.md diff --git a/common/tier4_state_rviz_plugin/icons/assets/active.png b/visualization/tier4_state_rviz_plugin/icons/assets/active.png similarity index 100% rename from common/tier4_state_rviz_plugin/icons/assets/active.png rename to visualization/tier4_state_rviz_plugin/icons/assets/active.png diff --git a/common/tier4_state_rviz_plugin/icons/assets/crash.png b/visualization/tier4_state_rviz_plugin/icons/assets/crash.png similarity index 100% rename from common/tier4_state_rviz_plugin/icons/assets/crash.png rename to visualization/tier4_state_rviz_plugin/icons/assets/crash.png diff --git a/common/tier4_state_rviz_plugin/icons/assets/danger.png b/visualization/tier4_state_rviz_plugin/icons/assets/danger.png similarity index 100% rename from common/tier4_state_rviz_plugin/icons/assets/danger.png rename to visualization/tier4_state_rviz_plugin/icons/assets/danger.png diff --git a/common/tier4_state_rviz_plugin/icons/assets/none.png b/visualization/tier4_state_rviz_plugin/icons/assets/none.png similarity index 100% rename from common/tier4_state_rviz_plugin/icons/assets/none.png rename to visualization/tier4_state_rviz_plugin/icons/assets/none.png diff --git a/common/tier4_state_rviz_plugin/icons/assets/pending.png b/visualization/tier4_state_rviz_plugin/icons/assets/pending.png similarity index 100% rename from common/tier4_state_rviz_plugin/icons/assets/pending.png rename to visualization/tier4_state_rviz_plugin/icons/assets/pending.png diff --git a/common/tier4_state_rviz_plugin/icons/classes/AutowareStatePanel.png b/visualization/tier4_state_rviz_plugin/icons/classes/AutowareStatePanel.png similarity index 100% rename from common/tier4_state_rviz_plugin/icons/classes/AutowareStatePanel.png rename to visualization/tier4_state_rviz_plugin/icons/classes/AutowareStatePanel.png diff --git a/common/tier4_state_rviz_plugin/icons/classes/VelocitySteeringFactorsPanel.png b/visualization/tier4_state_rviz_plugin/icons/classes/VelocitySteeringFactorsPanel.png similarity index 100% rename from common/tier4_state_rviz_plugin/icons/classes/VelocitySteeringFactorsPanel.png rename to visualization/tier4_state_rviz_plugin/icons/classes/VelocitySteeringFactorsPanel.png diff --git a/common/tier4_state_rviz_plugin/images/select_auto.png b/visualization/tier4_state_rviz_plugin/images/select_auto.png similarity index 100% rename from common/tier4_state_rviz_plugin/images/select_auto.png rename to visualization/tier4_state_rviz_plugin/images/select_auto.png diff --git a/common/tier4_state_rviz_plugin/images/select_panels.png b/visualization/tier4_state_rviz_plugin/images/select_panels.png similarity index 100% rename from common/tier4_state_rviz_plugin/images/select_panels.png rename to visualization/tier4_state_rviz_plugin/images/select_panels.png diff --git a/common/tier4_state_rviz_plugin/images/select_state_plugin.png b/visualization/tier4_state_rviz_plugin/images/select_state_plugin.png similarity index 100% rename from common/tier4_state_rviz_plugin/images/select_state_plugin.png rename to visualization/tier4_state_rviz_plugin/images/select_state_plugin.png diff --git a/common/tier4_state_rviz_plugin/package.xml b/visualization/tier4_state_rviz_plugin/package.xml similarity index 100% rename from common/tier4_state_rviz_plugin/package.xml rename to visualization/tier4_state_rviz_plugin/package.xml diff --git a/common/tier4_state_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_state_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_state_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_state_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/visualization/tier4_state_rviz_plugin/src/autoware_state_panel.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp rename to visualization/tier4_state_rviz_plugin/src/autoware_state_panel.cpp diff --git a/common/tier4_state_rviz_plugin/src/custom_button.cpp b/visualization/tier4_state_rviz_plugin/src/custom_button.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/custom_button.cpp rename to visualization/tier4_state_rviz_plugin/src/custom_button.cpp diff --git a/common/tier4_state_rviz_plugin/src/custom_container.cpp b/visualization/tier4_state_rviz_plugin/src/custom_container.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/custom_container.cpp rename to visualization/tier4_state_rviz_plugin/src/custom_container.cpp diff --git a/common/tier4_state_rviz_plugin/src/custom_icon_label.cpp b/visualization/tier4_state_rviz_plugin/src/custom_icon_label.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/custom_icon_label.cpp rename to visualization/tier4_state_rviz_plugin/src/custom_icon_label.cpp diff --git a/common/tier4_state_rviz_plugin/src/custom_label.cpp b/visualization/tier4_state_rviz_plugin/src/custom_label.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/custom_label.cpp rename to visualization/tier4_state_rviz_plugin/src/custom_label.cpp diff --git a/common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp b/visualization/tier4_state_rviz_plugin/src/custom_segmented_button.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/custom_segmented_button.cpp rename to visualization/tier4_state_rviz_plugin/src/custom_segmented_button.cpp diff --git a/common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp b/visualization/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp rename to visualization/tier4_state_rviz_plugin/src/custom_segmented_button_item.cpp diff --git a/common/tier4_state_rviz_plugin/src/custom_slider.cpp b/visualization/tier4_state_rviz_plugin/src/custom_slider.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/custom_slider.cpp rename to visualization/tier4_state_rviz_plugin/src/custom_slider.cpp diff --git a/common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp b/visualization/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp rename to visualization/tier4_state_rviz_plugin/src/custom_toggle_switch.cpp diff --git a/common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp b/visualization/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp rename to visualization/tier4_state_rviz_plugin/src/include/autoware_state_panel.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/custom_button.hpp b/visualization/tier4_state_rviz_plugin/src/include/custom_button.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/custom_button.hpp rename to visualization/tier4_state_rviz_plugin/src/include/custom_button.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/custom_container.hpp b/visualization/tier4_state_rviz_plugin/src/include/custom_container.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/custom_container.hpp rename to visualization/tier4_state_rviz_plugin/src/include/custom_container.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/custom_icon_label.hpp b/visualization/tier4_state_rviz_plugin/src/include/custom_icon_label.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/custom_icon_label.hpp rename to visualization/tier4_state_rviz_plugin/src/include/custom_icon_label.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/custom_label.hpp b/visualization/tier4_state_rviz_plugin/src/include/custom_label.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/custom_label.hpp rename to visualization/tier4_state_rviz_plugin/src/include/custom_label.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/custom_segmented_button.hpp b/visualization/tier4_state_rviz_plugin/src/include/custom_segmented_button.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/custom_segmented_button.hpp rename to visualization/tier4_state_rviz_plugin/src/include/custom_segmented_button.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp b/visualization/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp rename to visualization/tier4_state_rviz_plugin/src/include/custom_segmented_button_item.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/custom_slider.hpp b/visualization/tier4_state_rviz_plugin/src/include/custom_slider.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/custom_slider.hpp rename to visualization/tier4_state_rviz_plugin/src/include/custom_slider.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/custom_toggle_switch.hpp b/visualization/tier4_state_rviz_plugin/src/include/custom_toggle_switch.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/custom_toggle_switch.hpp rename to visualization/tier4_state_rviz_plugin/src/include/custom_toggle_switch.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/material_colors.hpp b/visualization/tier4_state_rviz_plugin/src/include/material_colors.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/material_colors.hpp rename to visualization/tier4_state_rviz_plugin/src/include/material_colors.hpp diff --git a/common/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp b/visualization/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp rename to visualization/tier4_state_rviz_plugin/src/include/velocity_steering_factors_panel.hpp diff --git a/common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp b/visualization/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp similarity index 100% rename from common/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp rename to visualization/tier4_state_rviz_plugin/src/velocity_steering_factors_panel.cpp diff --git a/common/tier4_system_rviz_plugin/CHANGELOG.rst b/visualization/tier4_system_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_system_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_system_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_system_rviz_plugin/CMakeLists.txt b/visualization/tier4_system_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_system_rviz_plugin/CMakeLists.txt rename to visualization/tier4_system_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_system_rviz_plugin/README.md b/visualization/tier4_system_rviz_plugin/README.md similarity index 100% rename from common/tier4_system_rviz_plugin/README.md rename to visualization/tier4_system_rviz_plugin/README.md diff --git a/common/tier4_system_rviz_plugin/package.xml b/visualization/tier4_system_rviz_plugin/package.xml similarity index 100% rename from common/tier4_system_rviz_plugin/package.xml rename to visualization/tier4_system_rviz_plugin/package.xml diff --git a/common/tier4_system_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_system_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_system_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_system_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_system_rviz_plugin/src/jsk_overlay_utils.cpp b/visualization/tier4_system_rviz_plugin/src/jsk_overlay_utils.cpp similarity index 100% rename from common/tier4_system_rviz_plugin/src/jsk_overlay_utils.cpp rename to visualization/tier4_system_rviz_plugin/src/jsk_overlay_utils.cpp diff --git a/common/tier4_system_rviz_plugin/src/jsk_overlay_utils.hpp b/visualization/tier4_system_rviz_plugin/src/jsk_overlay_utils.hpp similarity index 100% rename from common/tier4_system_rviz_plugin/src/jsk_overlay_utils.hpp rename to visualization/tier4_system_rviz_plugin/src/jsk_overlay_utils.hpp diff --git a/common/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp b/visualization/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp similarity index 100% rename from common/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp rename to visualization/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.cpp diff --git a/common/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.hpp b/visualization/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.hpp similarity index 100% rename from common/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.hpp rename to visualization/tier4_system_rviz_plugin/src/mrm_summary_overlay_display.hpp diff --git a/common/tier4_traffic_light_rviz_plugin/CHANGELOG.rst b/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_traffic_light_rviz_plugin/CMakeLists.txt b/visualization/tier4_traffic_light_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/CMakeLists.txt rename to visualization/tier4_traffic_light_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_traffic_light_rviz_plugin/README.md b/visualization/tier4_traffic_light_rviz_plugin/README.md similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/README.md rename to visualization/tier4_traffic_light_rviz_plugin/README.md diff --git a/common/tier4_traffic_light_rviz_plugin/icons/classes/TrafficLightPublishPanel.png b/visualization/tier4_traffic_light_rviz_plugin/icons/classes/TrafficLightPublishPanel.png similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/icons/classes/TrafficLightPublishPanel.png rename to visualization/tier4_traffic_light_rviz_plugin/icons/classes/TrafficLightPublishPanel.png diff --git a/common/tier4_traffic_light_rviz_plugin/images/select_panels.png b/visualization/tier4_traffic_light_rviz_plugin/images/select_panels.png similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/images/select_panels.png rename to visualization/tier4_traffic_light_rviz_plugin/images/select_panels.png diff --git a/common/tier4_traffic_light_rviz_plugin/images/select_traffic_light_id.png b/visualization/tier4_traffic_light_rviz_plugin/images/select_traffic_light_id.png similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/images/select_traffic_light_id.png rename to visualization/tier4_traffic_light_rviz_plugin/images/select_traffic_light_id.png diff --git a/common/tier4_traffic_light_rviz_plugin/images/select_traffic_light_publish_panel.png b/visualization/tier4_traffic_light_rviz_plugin/images/select_traffic_light_publish_panel.png similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/images/select_traffic_light_publish_panel.png rename to visualization/tier4_traffic_light_rviz_plugin/images/select_traffic_light_publish_panel.png diff --git a/common/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif b/visualization/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif rename to visualization/tier4_traffic_light_rviz_plugin/images/traffic_light_publish_panel.gif diff --git a/common/tier4_traffic_light_rviz_plugin/package.xml b/visualization/tier4_traffic_light_rviz_plugin/package.xml similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/package.xml rename to visualization/tier4_traffic_light_rviz_plugin/package.xml diff --git a/common/tier4_traffic_light_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_traffic_light_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_traffic_light_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp b/visualization/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp rename to visualization/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp diff --git a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp b/visualization/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp similarity index 100% rename from common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp rename to visualization/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.hpp diff --git a/common/tier4_vehicle_rviz_plugin/CHANGELOG.rst b/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst similarity index 100% rename from common/tier4_vehicle_rviz_plugin/CHANGELOG.rst rename to visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst diff --git a/common/tier4_vehicle_rviz_plugin/CMakeLists.txt b/visualization/tier4_vehicle_rviz_plugin/CMakeLists.txt similarity index 100% rename from common/tier4_vehicle_rviz_plugin/CMakeLists.txt rename to visualization/tier4_vehicle_rviz_plugin/CMakeLists.txt diff --git a/common/tier4_vehicle_rviz_plugin/README.md b/visualization/tier4_vehicle_rviz_plugin/README.md similarity index 100% rename from common/tier4_vehicle_rviz_plugin/README.md rename to visualization/tier4_vehicle_rviz_plugin/README.md diff --git a/common/tier4_vehicle_rviz_plugin/icons/classes/AccelerationMeter.png b/visualization/tier4_vehicle_rviz_plugin/icons/classes/AccelerationMeter.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/icons/classes/AccelerationMeter.png rename to visualization/tier4_vehicle_rviz_plugin/icons/classes/AccelerationMeter.png diff --git a/common/tier4_vehicle_rviz_plugin/icons/classes/ConsoleMeter.png b/visualization/tier4_vehicle_rviz_plugin/icons/classes/ConsoleMeter.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/icons/classes/ConsoleMeter.png rename to visualization/tier4_vehicle_rviz_plugin/icons/classes/ConsoleMeter.png diff --git a/common/tier4_vehicle_rviz_plugin/icons/classes/SteeringAngle.png b/visualization/tier4_vehicle_rviz_plugin/icons/classes/SteeringAngle.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/icons/classes/SteeringAngle.png rename to visualization/tier4_vehicle_rviz_plugin/icons/classes/SteeringAngle.png diff --git a/common/tier4_vehicle_rviz_plugin/icons/classes/TurnSignal.png b/visualization/tier4_vehicle_rviz_plugin/icons/classes/TurnSignal.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/icons/classes/TurnSignal.png rename to visualization/tier4_vehicle_rviz_plugin/icons/classes/TurnSignal.png diff --git a/common/tier4_vehicle_rviz_plugin/icons/classes/VelocityHistory.png b/visualization/tier4_vehicle_rviz_plugin/icons/classes/VelocityHistory.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/icons/classes/VelocityHistory.png rename to visualization/tier4_vehicle_rviz_plugin/icons/classes/VelocityHistory.png diff --git a/common/tier4_vehicle_rviz_plugin/images/handle.png b/visualization/tier4_vehicle_rviz_plugin/images/handle.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/images/handle.png rename to visualization/tier4_vehicle_rviz_plugin/images/handle.png diff --git a/common/tier4_vehicle_rviz_plugin/images/select_add.png b/visualization/tier4_vehicle_rviz_plugin/images/select_add.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/images/select_add.png rename to visualization/tier4_vehicle_rviz_plugin/images/select_add.png diff --git a/common/tier4_vehicle_rviz_plugin/images/select_topic_name.png b/visualization/tier4_vehicle_rviz_plugin/images/select_topic_name.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/images/select_topic_name.png rename to visualization/tier4_vehicle_rviz_plugin/images/select_topic_name.png diff --git a/common/tier4_vehicle_rviz_plugin/images/select_vehicle_plugin.png b/visualization/tier4_vehicle_rviz_plugin/images/select_vehicle_plugin.png similarity index 100% rename from common/tier4_vehicle_rviz_plugin/images/select_vehicle_plugin.png rename to visualization/tier4_vehicle_rviz_plugin/images/select_vehicle_plugin.png diff --git a/common/tier4_vehicle_rviz_plugin/package.xml b/visualization/tier4_vehicle_rviz_plugin/package.xml similarity index 100% rename from common/tier4_vehicle_rviz_plugin/package.xml rename to visualization/tier4_vehicle_rviz_plugin/package.xml diff --git a/common/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml b/visualization/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml similarity index 100% rename from common/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml rename to visualization/tier4_vehicle_rviz_plugin/plugins/plugin_description.xml diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.cpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/acceleration_meter.hpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/console_meter.cpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/console_meter.hpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.cpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.cpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.cpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.cpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.hpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.hpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.hpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/jsk_overlay_utils.hpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/steering_angle.cpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.hpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/steering_angle.hpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/steering_angle.hpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/steering_angle.hpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/turn_signal.cpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/turn_signal.cpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/turn_signal.cpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/turn_signal.cpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/turn_signal.hpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/turn_signal.hpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/turn_signal.hpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/turn_signal.hpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/velocity_history.cpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/velocity_history.cpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/velocity_history.cpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/velocity_history.cpp diff --git a/common/tier4_vehicle_rviz_plugin/src/tools/velocity_history.hpp b/visualization/tier4_vehicle_rviz_plugin/src/tools/velocity_history.hpp similarity index 100% rename from common/tier4_vehicle_rviz_plugin/src/tools/velocity_history.hpp rename to visualization/tier4_vehicle_rviz_plugin/src/tools/velocity_history.hpp From 30f0a2ef0ab485536d8331afc2b29e5b7c473d33 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 10 Dec 2024 13:49:36 +0900 Subject: [PATCH 257/273] revert(CODEOWNERS): revert accidental rename (#9605) Signed-off-by: Zulfaqar Azmi --- .github/{_CODEOWNERS => CODEOWNERS} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename .github/{_CODEOWNERS => CODEOWNERS} (100%) diff --git a/.github/_CODEOWNERS b/.github/CODEOWNERS similarity index 100% rename from .github/_CODEOWNERS rename to .github/CODEOWNERS From 1d96a7f10104fc85468a0720a4b918864a14b624 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Tue, 10 Dec 2024 17:34:30 +0900 Subject: [PATCH 258/273] feat(diagnostic_graph_utils): publish error graph instead of the terminal log (#9421) * feat(diagnostic_graph_utils): publish error graph instead of the terminal log Signed-off-by: Takayuki Murooka * update Signed-off-by: Takayuki Murooka * fix Signed-off-by: Takayuki Murooka * Update system/diagnostic_graph_utils/src/node/logging.cpp Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> * error_graph -> error_graph_text Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> --- .../launch/logging.launch.xml | 1 + system/diagnostic_graph_utils/package.xml | 1 + .../src/node/logging.cpp | 25 ++++++++++++++++--- .../src/node/logging.hpp | 4 +++ 4 files changed, 27 insertions(+), 4 deletions(-) diff --git a/system/diagnostic_graph_utils/launch/logging.launch.xml b/system/diagnostic_graph_utils/launch/logging.launch.xml index 12636574eb8be..f14a045919599 100644 --- a/system/diagnostic_graph_utils/launch/logging.launch.xml +++ b/system/diagnostic_graph_utils/launch/logging.launch.xml @@ -6,5 +6,6 @@ + diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml index d558ba26b636a..69b8e4083356d 100644 --- a/system/diagnostic_graph_utils/package.xml +++ b/system/diagnostic_graph_utils/package.xml @@ -13,6 +13,7 @@ diagnostic_msgs rclcpp rclcpp_components + tier4_debug_msgs tier4_system_msgs ament_lint_auto diff --git a/system/diagnostic_graph_utils/src/node/logging.cpp b/system/diagnostic_graph_utils/src/node/logging.cpp index b166a087200a0..5d360a00aee82 100644 --- a/system/diagnostic_graph_utils/src/node/logging.cpp +++ b/system/diagnostic_graph_utils/src/node/logging.cpp @@ -34,8 +34,13 @@ LoggingNode::LoggingNode(const rclcpp::NodeOptions & options) : Node("logging", sub_graph_.register_create_callback(std::bind(&LoggingNode::on_create, this, _1)); sub_graph_.subscribe(*this, 1); + pub_error_graph_text_ = create_publisher( + "~/debug/error_graph_text", rclcpp::QoS(1)); + const auto period = rclcpp::Rate(declare_parameter("show_rate")).period(); timer_ = rclcpp::create_timer(this, get_clock(), period, [this]() { on_timer(); }); + + enable_terminal_log_ = declare_parameter("enable_terminal_log"); } void LoggingNode::on_create(DiagGraph::ConstSharedPtr graph) @@ -53,12 +58,24 @@ void LoggingNode::on_create(DiagGraph::ConstSharedPtr graph) void LoggingNode::on_timer() { - static const auto message = "The target mode is not available for the following reasons:"; + static const auto prefix_message = "The target mode is not available for the following reasons:"; if (root_unit_ && root_unit_->level() != DiagUnit::DiagnosticStatus::OK) { dump_text_.str(""); dump_text_.clear(std::stringstream::goodbit); - dump_unit(root_unit_, 0, " "); - RCLCPP_WARN_STREAM(get_logger(), message << std::endl << dump_text_.str()); + dump_unit(root_unit_, 0, ""); + + if (enable_terminal_log_) { + RCLCPP_WARN_STREAM(get_logger(), prefix_message << std::endl << dump_text_.str()); + } + + tier4_debug_msgs::msg::StringStamped message; + message.stamp = now(); + message.data = dump_text_.str(); + pub_error_graph_text_->publish(message); + } else { + tier4_debug_msgs::msg::StringStamped message; + message.stamp = now(); + pub_error_graph_text_->publish(message); } } @@ -86,7 +103,7 @@ void LoggingNode::dump_unit(DiagUnit * unit, int depth, const std::string & inde dump_text_ << indent << "- " + path << " " << text_level(unit->level()) << std::endl; for (const auto & child : unit->children()) { - dump_unit(child.unit, depth + 1, indent + " "); + dump_unit(child.unit, depth + 1, indent + " "); } } diff --git a/system/diagnostic_graph_utils/src/node/logging.hpp b/system/diagnostic_graph_utils/src/node/logging.hpp index b2d305c81ca99..17d33499a1513 100644 --- a/system/diagnostic_graph_utils/src/node/logging.hpp +++ b/system/diagnostic_graph_utils/src/node/logging.hpp @@ -19,6 +19,8 @@ #include +#include "tier4_debug_msgs/msg/string_stamped.hpp" + #include #include @@ -35,12 +37,14 @@ class LoggingNode : public rclcpp::Node void on_timer(); void dump_unit(DiagUnit * unit, int depth, const std::string & indent); DiagGraphSubscription sub_graph_; + rclcpp::Publisher::SharedPtr pub_error_graph_text_; rclcpp::TimerBase::SharedPtr timer_; DiagUnit * root_unit_; int max_depth_; std::string root_path_; std::ostringstream dump_text_; + bool enable_terminal_log_; }; } // namespace diagnostic_graph_utils From c0c70cc5dfcf1d1be935999ffc5b7b092a0973c9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 10 Dec 2024 15:56:54 +0300 Subject: [PATCH 259/273] ci(pr-agent): reduce the contents:write permission to read for security (#9598) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/workflows/pr-agent.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/pr-agent.yaml b/.github/workflows/pr-agent.yaml index 5cd0845b3d9b4..a60e65ccf7b32 100644 --- a/.github/workflows/pr-agent.yaml +++ b/.github/workflows/pr-agent.yaml @@ -17,7 +17,7 @@ jobs: permissions: issues: write pull-requests: write - contents: write + contents: read name: Run pr agent on every pull request, respond to user comments steps: - name: PR Agent action step @@ -35,6 +35,7 @@ jobs: config.model_turbo: gpt-4o config.max_model_tokens: 64000 pr_code_suggestions.max_context_tokens: 12000 + # cSpell:ignore commitable pr_code_suggestions.commitable_code_suggestions: true pr_reviewer.enable_review_labels_effort: false pr_reviewer.enable_review_labels_security: false From 8ba1699b7482d328be25b26ecb697e3d48a698d3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?M=2E=20Fatih=20C=C4=B1r=C4=B1t?= Date: Tue, 10 Dec 2024 16:56:10 +0300 Subject: [PATCH 260/273] ci(build-and-test): use self hosted X64 and add ccache to -daily (#9601) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: M. Fatih Cırıt --- .github/workflows/build-and-test-daily.yaml | 40 ++++++++++++++++++++- .github/workflows/build-and-test.yaml | 2 +- 2 files changed, 40 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-and-test-daily.yaml b/.github/workflows/build-and-test-daily.yaml index 63822f8b1e093..b2612f2fcd1f0 100644 --- a/.github/workflows/build-and-test-daily.yaml +++ b/.github/workflows/build-and-test-daily.yaml @@ -5,9 +5,13 @@ on: - cron: 0 0 * * * workflow_dispatch: +env: + CC: /usr/lib/ccache/gcc + CXX: /usr/lib/ccache/g++ + jobs: build-and-test-daily: - runs-on: [self-hosted, linux, X64, gpu] + runs-on: [self-hosted, Linux, X64] container: ${{ matrix.container }}${{ matrix.container-suffix }} strategy: fail-fast: false @@ -30,6 +34,9 @@ jobs: - name: Show disk space before the tasks run: df -h + - name: Show machine specs + run: lscpu && free -h + - name: Remove exec_depend uses: autowarefoundation/autoware-github-actions/remove-exec-depend@v1 @@ -37,6 +44,33 @@ jobs: id: get-self-packages uses: autowarefoundation/autoware-github-actions/get-self-packages@v1 + - name: Create ccache directory + run: | + mkdir -p ${CCACHE_DIR} + du -sh ${CCACHE_DIR} && ccache -s + shell: bash + + - name: Attempt to restore ccache + uses: actions/cache/restore@v4 + with: + path: | + /root/.ccache + key: ccache-main-${{ runner.arch }}-${{ matrix.rosdistro }}-${{ github.sha }} + restore-keys: | + ccache-main-${{ runner.arch }}-${{ matrix.rosdistro }}- + + - name: Limit ccache size + run: | + rm -f "${CCACHE_DIR}/ccache.conf" + echo -e "# Set maximum cache size\nmax_size = 600MB" >> "${CCACHE_DIR}/ccache.conf" + shell: bash + + - name: Show ccache stats before build and reset stats + run: | + du -sh ${CCACHE_DIR} && ccache -s + ccache --zero-stats + shell: bash + - name: Export CUDA state as a variable for adding to cache key run: | build_type_cuda_state=nocuda @@ -56,6 +90,10 @@ jobs: build-depends-repos: ${{ matrix.build-depends-repos }} cache-key-element: ${{ env.BUILD_TYPE_CUDA_STATE }} + - name: Show ccache stats after build + run: du -sh ${CCACHE_DIR} && ccache -s + shell: bash + - name: Test if: ${{ steps.get-self-packages.outputs.self-packages != '' }} id: test diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 3ffa5ebdbd29d..6b3886f124a44 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -16,7 +16,7 @@ env: jobs: build-and-test: - runs-on: codebuild-autoware-us-east-1-${{ github.run_id }}-${{ github.run_attempt }}-ubuntu-7.0-large + runs-on: [self-hosted, Linux, X64] container: ${{ matrix.container }}${{ matrix.container-suffix }} strategy: fail-fast: false From 9707caf3bff95964d17cadd69575286c1bb7ed98 Mon Sep 17 00:00:00 2001 From: "awf-autoware-bot[bot]" <94889083+awf-autoware-bot[bot]@users.noreply.github.com> Date: Tue, 10 Dec 2024 14:43:01 +0000 Subject: [PATCH 261/273] chore: update CODEOWNERS (#9577) Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: github-actions --- .github/CODEOWNERS | 35 +++++++++++++++++------------------ 1 file changed, 17 insertions(+), 18 deletions(-) diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index 3c1defb31a741..7403da173eb13 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -5,7 +5,6 @@ common/autoware_component_interface_specs/** isamu.takagi@tier4.jp yukihiro.sait common/autoware_component_interface_tools/** isamu.takagi@tier4.jp common/autoware_component_interface_utils/** isamu.takagi@tier4.jp yukihiro.saito@tier4.jp common/autoware_fake_test_node/** opensource@apex.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp -common/autoware_geography_utils/** anh.nguyen.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp common/autoware_global_parameter_loader/** ryohsuke.mitsudome@tier4.jp common/autoware_glog_component/** takamasa.horibe@tier4.jp common/autoware_goal_distance_calculator/** taiki.tanaka@tier4.jp @@ -15,12 +14,10 @@ common/autoware_kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yu 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_object_recognition_utils/** shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yoshi.ri@tier4.jp common/autoware_osqp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@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_polar_grid/** yukihiro.saito@tier4.jp +common/autoware_pyplot/** mamoru.sobue@tier4.jp yukinari.hisaki.2@tier4.jp common/autoware_qp_interface/** fumiya.watanabe@tier4.jp maxime.clement@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp common/autoware_signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/autoware_test_utils/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp zulfaqar.azmi@tier4.jp @@ -31,18 +28,8 @@ common/autoware_traffic_light_utils/** kotaro.uetake@tier4.jp satoshi.ota@tier4. common/autoware_trajectory/** mamoru.sobue@tier4.jp takayuki.murooka@tier4.jp yukinari.hisaki.2@tier4.jp common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp common/autoware_vehicle_info_utils/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp -common/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp -common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp common/tier4_api_utils/** isamu.takagi@tier4.jp -common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp -common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp -common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp yamato.ando@tier4.jp -common/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp -common/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp khalil@leodrive.ai -common/tier4_system_rviz_plugin/** koji.minoda@tier4.jp -common/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp -common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp -control/autoware_autonomous_emergency_braking/** daniel.sanchez@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp +control/autoware_autonomous_emergency_braking/** alqudah.mohammad@tier4.jp daniel.sanchez@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp tomoya.kimura@tier4.jp control/autoware_collision_detector/** go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp tomohito.ando@tier4.jp control/autoware_control_validator/** kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp control/autoware_external_cmd_selector/** fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp @@ -173,7 +160,7 @@ planning/behavior_path_planner/autoware_behavior_path_planner_common/** alqudah. planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/** daniel.sanchez@tier4.jp maxime.clement@tier4.jp planning/behavior_path_planner/autoware_behavior_path_side_shift_module/** fumiya.watanabe@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp planning/behavior_path_planner/autoware_behavior_path_start_planner_module/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp -planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp zulfaqar.azmi@tier4.jp +planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/** fumiya.watanabe@tier4.jp go.sakayori@tier4.jp kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp tomohito.ando@tier4.jp tomoya.kimura@tier4.jp yukinari.hisaki.2@tier4.jp zulfaqar.azmi@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/** mamoru.sobue@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp yukinari.hisaki.2@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/** kyoichi.sugahara@tier4.jp mamoru.sobue@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp yuki.takagi@tier4.jp planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/** kyoichi.sugahara@tier4.jp shumpei.wakabayashi@tier4.jp tomoya.kimura@tier4.jp @@ -210,8 +197,8 @@ sensing/autoware_radar_scan_to_pointcloud2/** satoshi.tanaka@tier4.jp shunsuke.m sensing/autoware_radar_static_pointcloud_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/autoware_radar_threshold_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp sensing/autoware_radar_tracks_noise_filter/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp taekjin.lee@tier4.jp yoshi.ri@tier4.jp -sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp sensing/autoware_vehicle_velocity_converter/** ryu.yamamoto@tier4.jp +sensing/livox/autoware_livox_tag_filter/** kenzo.lobos@tier4.jp ryohsuke.mitsudome@tier4.jp simulator/autoware_carla_interface/** maxime.clement@tier4.jp mradityagio@gmail.com simulator/dummy_perception_publisher/** yukihiro.saito@tier4.jp simulator/fault_injection/** keisuke.shima@tier4.jp @@ -245,6 +232,18 @@ vehicle/autoware_accel_brake_map_calibrator/** eiki.nagata.2@tier4.jp taiki.tana vehicle/autoware_external_cmd_converter/** eiki.nagata.2@tier4.jp takamasa.horibe@tier4.jp vehicle/autoware_raw_vehicle_cmd_converter/** kosuke.takeuchi@tier4.jp kyoichi.sugahara@tier4.jp makoto.kurihara@tier4.jp sho.iwasawa.2@tier4.jp taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp vehicle/autoware_steer_offset_estimator/** taiki.tanaka@tier4.jp -visualization/autoware_pyplot/** mamoru.sobue@tier4.jp yukinari.hisaki.2@tier4.jp +visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/** ahmed.ebrahim@leodrive.ai +visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/** khalil@leodrive.ai +visualization/autoware_perception_rviz_plugin/** opensource@apex.ai shunsuke.miura@tier4.jp taiki.tanaka@tier4.jp takeshi.miura@tier4.jp yoshi.ri@tier4.jp +visualization/bag_time_manager_rviz_plugin/** taiki.tanaka@tier4.jp +visualization/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp +visualization/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp +visualization/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp +visualization/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp yamato.ando@tier4.jp +visualization/tier4_planning_rviz_plugin/** takayuki.murooka@tier4.jp yukihiro.saito@tier4.jp +visualization/tier4_state_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp khalil@leodrive.ai +visualization/tier4_system_rviz_plugin/** koji.minoda@tier4.jp +visualization/tier4_traffic_light_rviz_plugin/** satoshi.ota@tier4.jp +visualization/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp ### Copied from .github/CODEOWNERS-manual ### From 34f7c9b92cb6edd89310aced8c9b499412915935 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 11 Dec 2024 01:02:39 +0900 Subject: [PATCH 262/273] feat(behavior_path_planner): add detail text to virutal wall (#9600) * feat(behavior_path_planner): add detail text to virutal wall Signed-off-by: kosuke55 * goal is far Signed-off-by: kosuke55 * pull over start pose is far Signed-off-by: kosuke55 * fix lc build Signed-off-by: kosuke55 * fix build Signed-off-by: kosuke55 * Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../goal_planner_module.hpp | 33 ++----- .../src/goal_planner_module.cpp | 93 ++++++++----------- .../src/interface.cpp | 8 +- .../data_manager.hpp | 11 +++ .../interface/scene_module_interface.hpp | 28 +++--- .../scene_module_manager_interface.hpp | 38 ++++---- .../utils/parking_departure/utils.hpp | 3 +- .../src/utils/parking_departure/utils.cpp | 5 +- .../test/test_parking_departure_utils.cpp | 3 +- .../start_planner_module.hpp | 2 +- .../src/start_planner_module.cpp | 2 +- .../utils.hpp | 2 +- .../src/scene.cpp | 17 ++-- .../src/utils.cpp | 4 +- .../test/test_utils.cpp | 10 +- 15 files changed, 123 insertions(+), 136 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 09acced162abd..5e6afa16d1f9f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -84,29 +84,6 @@ struct LastApprovalData Pose pose{}; }; -// store stop_pose_ pointer with reason string -struct PoseWithString -{ - std::optional * pose; - std::string string; - - explicit PoseWithString(std::optional * shared_pose) : pose(shared_pose), string("") {} - - void set(const Pose & new_pose, const std::string & new_string) - { - *pose = new_pose; - string = new_string; - } - - void set(const std::string & new_string) { string = new_string; } - - void clear() - { - pose->reset(); - string = ""; - } -}; - struct PullOverContextData { PullOverContextData() = delete; @@ -371,7 +348,6 @@ class GoalPlannerModule : public SceneModuleInterface // debug mutable GoalPlannerDebugData debug_data_; - mutable PoseWithString debug_stop_pose_with_info_; // goal seach GoalCandidates generateGoalCandidates() const; @@ -381,8 +357,10 @@ class GoalPlannerModule : public SceneModuleInterface void decelerateForTurnSignal(const Pose & stop_pose, PathWithLaneId & path) const; void decelerateBeforeSearchStart( const Pose & search_start_offset_pose, PathWithLaneId & path) const; - PathWithLaneId generateStopPath(const PullOverContextData & context_data) const; - PathWithLaneId generateFeasibleStopPath(const PathWithLaneId & path) const; + PathWithLaneId generateStopPath( + const PullOverContextData & context_data, const std::string & detail) const; + PathWithLaneId generateFeasibleStopPath( + const PathWithLaneId & path, const std::string & detail) const; void keepStoppedWithCurrentPath( const PullOverContextData & ctx_data, PathWithLaneId & path) const; @@ -420,7 +398,8 @@ class GoalPlannerModule : public SceneModuleInterface // plan pull over path BehaviorModuleOutput planPullOver(const PullOverContextData & context_data); BehaviorModuleOutput planPullOverAsOutput(const PullOverContextData & context_data); - BehaviorModuleOutput planPullOverAsCandidate(const PullOverContextData & context_data); + BehaviorModuleOutput planPullOverAsCandidate( + const PullOverContextData & context_data, const std::string & detail); std::optional selectPullOverPath( const PullOverContextData & context_data, const std::vector & pull_over_path_candidates, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 716047c7ad1f1..e1f667d91b692 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -72,8 +72,7 @@ GoalPlannerModule::GoalPlannerModule( vehicle_info_{autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo()}, thread_safe_data_{mutex_, clock_}, is_lane_parking_cb_running_{false}, - is_freespace_parking_cb_running_{false}, - debug_stop_pose_with_info_{&stop_pose_} + is_freespace_parking_cb_running_{false} { LaneDepartureChecker lane_departure_checker{}; lane_departure_checker.setVehicleInfo(vehicle_info_); @@ -1237,7 +1236,8 @@ void GoalPlannerModule::setOutput( if (!context_data.pull_over_path_opt) { // situation : not safe against static objects use stop_path - output.path = generateStopPath(context_data); + output.path = generateStopPath( + context_data, (goal_candidates_.empty() ? "no goal candidate" : "no static safe path")); RCLCPP_INFO_THROTTLE( getLogger(), *clock_, 5000, "Not found safe pull_over path, generate stop path"); setDrivableAreaInfo(context_data, output); @@ -1251,10 +1251,10 @@ void GoalPlannerModule::setOutput( // situation : not safe against dynamic objects after approval // insert stop point in current path if ego is able to stop with acceleration and jerk // constraints - output.path = generateFeasibleStopPath(pull_over_path.getCurrentPath()); + output.path = + generateFeasibleStopPath(pull_over_path.getCurrentPath(), "unsafe against dynamic objects"); RCLCPP_INFO_THROTTLE( getLogger(), *clock_, 5000, "Not safe against dynamic objects, generate stop path"); - debug_stop_pose_with_info_.set(std::string("feasible stop after approval")); } else { // situation : (safe against static and dynamic objects) or (safe against static objects and // before approval) don't stop @@ -1363,17 +1363,25 @@ BehaviorModuleOutput GoalPlannerModule::planPullOver(const PullOverContextData & { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); - if ( - path_decision_controller_.get_current_state().state != - PathDecisionState::DecisionKind::DECIDED) { - return planPullOverAsCandidate(context_data); + const auto current_state = path_decision_controller_.get_current_state(); + if (current_state.state != PathDecisionState::DecisionKind::DECIDED) { + const bool is_stable_safe = current_state.is_stable_safe; + // clang-format off + const std::string detail = + goal_candidates_.empty() ? "no goal candidate" : + context_data.pull_over_path_candidates.empty() ? "no path candidate" : + !thread_safe_data_.foundPullOverPath() ? "no static safe path" : + !is_stable_safe ? "unsafe against dynamic objects" : + "too far goal"; + // clang-format on + return planPullOverAsCandidate(context_data, detail); } return planPullOverAsOutput(context_data); } BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate( - const PullOverContextData & context_data) + const PullOverContextData & context_data, const std::string & detail) { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1385,7 +1393,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsCandidate( BehaviorModuleOutput output{}; const BehaviorModuleOutput pull_over_output = planPullOverAsOutput(context_data); output.modified_goal = pull_over_output.modified_goal; - output.path = generateStopPath(context_data); + output.path = generateStopPath(context_data, detail); output.reference_path = getPreviousModuleOutput().reference_path; const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( @@ -1560,7 +1568,7 @@ BehaviorModuleOutput GoalPlannerModule::planWaitingApproval() "planner"); } else { const auto & context_data = context_data_.value(); - return planPullOverAsCandidate(context_data); + return planPullOverAsCandidate(context_data, "waiting approval"); } } @@ -1606,7 +1614,8 @@ void GoalPlannerModule::setParameters(const std::shared_ptr std::optional> { - if (context_data.pull_over_path_opt) { - return std::make_pair( - context_data.pull_over_path_opt.value().start_pose(), "stop at selected start pose"); - } - if (thread_safe_data_.get_closest_start_pose()) { - return std::make_pair( - thread_safe_data_.get_closest_start_pose().value(), "stop at closest start pose"); - } - if (!decel_pose) { - return std::nullopt; - } - return std::make_pair(decel_pose.value(), "stop at search start pose"); - }); - if (!stop_pose_with_info) { - const auto feasible_stop_path = generateFeasibleStopPath(getPreviousModuleOutput().path); - // override stop pose info debug string - debug_stop_pose_with_info_.set(std::string("feasible stop: not calculate stop pose")); + const auto stop_pose_opt = std::invoke([&]() -> std::optional { + if (context_data.pull_over_path_opt) + return context_data.pull_over_path_opt.value().start_pose(); + if (thread_safe_data_.get_closest_start_pose()) + return thread_safe_data_.get_closest_start_pose().value(); + if (!decel_pose) return std::nullopt; + return decel_pose.value(); + }); + if (!stop_pose_opt.has_value()) { + const auto feasible_stop_path = + generateFeasibleStopPath(getPreviousModuleOutput().path, detail); return feasible_stop_path; } - const Pose stop_pose = stop_pose_with_info->first; + const Pose stop_pose = stop_pose_opt.value(); // if stop pose is closer than min_stop_distance, stop as soon as possible const double ego_to_stop_distance = calcSignedArcLengthFromEgo(extended_prev_path, stop_pose); @@ -1687,16 +1688,15 @@ PathWithLaneId GoalPlannerModule::generateStopPath(const PullOverContextData & c const bool is_stopped = std::abs(current_vel) < eps_vel; const double buffer = is_stopped ? stop_distance_buffer_ : 0.0; if (min_stop_distance && ego_to_stop_distance + buffer < *min_stop_distance) { - const auto feasible_stop_path = generateFeasibleStopPath(getPreviousModuleOutput().path); - debug_stop_pose_with_info_.set( - std::string("feasible stop: stop pose is closer than min_stop_distance")); + const auto feasible_stop_path = + generateFeasibleStopPath(getPreviousModuleOutput().path, detail); return feasible_stop_path; } // slow down for turn signal, insert stop point to stop_pose auto stop_path = extended_prev_path; decelerateForTurnSignal(stop_pose, stop_path); - debug_stop_pose_with_info_.set(stop_pose, stop_pose_with_info->second); + stop_pose_ = PoseWithDetail(stop_pose, detail); // slow down before the search area. if (decel_pose) { @@ -1719,7 +1719,8 @@ PathWithLaneId GoalPlannerModule::generateStopPath(const PullOverContextData & c return stop_path; } -PathWithLaneId GoalPlannerModule::generateFeasibleStopPath(const PathWithLaneId & path) const +PathWithLaneId GoalPlannerModule::generateFeasibleStopPath( + const PathWithLaneId & path, const std::string & detail) const { universe_utils::ScopedTimeTrack st(__func__, *time_keeper_); @@ -1736,7 +1737,7 @@ PathWithLaneId GoalPlannerModule::generateFeasibleStopPath(const PathWithLaneId const auto stop_idx = autoware::motion_utils::insertStopPoint(current_pose, *min_stop_distance, stop_path.points); if (stop_idx) { - debug_stop_pose_with_info_.set(stop_path.points.at(*stop_idx).point.pose, "feasible stop"); + stop_pose_ = PoseWithDetail(stop_path.points.at(*stop_idx).point.pose, detail); } return stop_path; @@ -2564,20 +2565,6 @@ void GoalPlannerModule::setDebugData(const PullOverContextData & context_data) planner_type_marker_array.markers.push_back(marker); add(planner_type_marker_array); } - - // Visualize stop pose info - if (debug_stop_pose_with_info_.pose->has_value()) { - visualization_msgs::msg::MarkerArray stop_pose_marker_array{}; - const auto color = createMarkerColor(1.0, 1.0, 1.0, 0.99); - auto marker = createDefaultMarker( - header.frame_id, header.stamp, "stop_pose_info", 0, - visualization_msgs::msg::Marker::TEXT_VIEW_FACING, createMarkerScale(0.0, 0.0, 0.5), color); - marker.pose = debug_stop_pose_with_info_.pose->value(); - marker.text = debug_stop_pose_with_info_.string; - stop_pose_marker_array.markers.push_back(marker); - add(stop_pose_marker_array); - add(createPoseMarkerArray(marker.pose, "stop_pose", 1.0, 1.0, 1.0, 0.9)); - } } void GoalPlannerModule::GoalPlannerData::initializeOccupancyGridMap( diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp index f80aad721a07c..d65e51997eb32 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/interface.cpp @@ -111,7 +111,9 @@ BehaviorModuleOutput LaneChangeInterface::plan() path_reference_ = std::make_shared(output.reference_path); *prev_approved_path_ = getPreviousModuleOutput().path; - stop_pose_ = module_type_->getStopPose(); + const auto stop_pose_opt = module_type_->getStopPose(); + stop_pose_ = stop_pose_opt.has_value() ? PoseWithDetailOpt(PoseWithDetail(stop_pose_opt.value())) + : PoseWithDetailOpt(); const auto & lane_change_debug = module_type_->getDebugData(); for (const auto & [uuid, data] : lane_change_debug.collision_check_objects_after_approval) { @@ -169,7 +171,9 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval() } path_reference_ = std::make_shared(out.reference_path); - stop_pose_ = module_type_->getStopPose(); + const auto stop_pose_opt = module_type_->getStopPose(); + stop_pose_ = stop_pose_opt.has_value() ? PoseWithDetailOpt(PoseWithDetail(stop_pose_opt.value())) + : PoseWithDetailOpt(); if (!module_type_->isValidPath()) { path_candidate_ = std::make_shared(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp index 27f0dc4e58178..31d1f0072fe5c 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp @@ -147,6 +147,17 @@ struct CandidateOutput double finish_distance_to_path_change{std::numeric_limits::lowest()}; }; +/** + * @brief Adds detail text to stop/slow/dead_pose virtual walls. + */ +struct PoseWithDetail +{ + Pose pose; + std::string detail; + explicit PoseWithDetail(const Pose & p, const std::string & d = "") : pose(p), detail(d) {} +}; +using PoseWithDetailOpt = std::optional; + struct PlannerData { Odometry::ConstSharedPtr self_odometry{}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp index 9fc4113e87d9e..391ac92411220 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp @@ -270,34 +270,40 @@ class SceneModuleInterface std::string name() const { return name_; } - std::optional getStopPose() const + PoseWithDetailOpt getStopPose() const { if (!stop_pose_) { return {}; } const auto & base_link2front = planner_data_->parameters.base_link2front; - return calcOffsetPose(stop_pose_.value(), base_link2front, 0.0, 0.0); + return PoseWithDetail( + calcOffsetPose(stop_pose_.value().pose, base_link2front, 0.0, 0.0), + stop_pose_.value().detail); } - std::optional getSlowPose() const + PoseWithDetailOpt getSlowPose() const { if (!slow_pose_) { return {}; } const auto & base_link2front = planner_data_->parameters.base_link2front; - return calcOffsetPose(slow_pose_.value(), base_link2front, 0.0, 0.0); + return PoseWithDetail( + calcOffsetPose(slow_pose_.value().pose, base_link2front, 0.0, 0.0), + slow_pose_.value().detail); } - std::optional getDeadPose() const + PoseWithDetailOpt getDeadPose() const { if (!dead_pose_) { return {}; } const auto & base_link2front = planner_data_->parameters.base_link2front; - return calcOffsetPose(dead_pose_.value(), base_link2front, 0.0, 0.0); + return PoseWithDetail( + calcOffsetPose(dead_pose_.value().pose, base_link2front, 0.0, 0.0), + dead_pose_.value().detail); } void resetWallPoses() const @@ -556,7 +562,7 @@ class SceneModuleInterface { if (stop_pose_.has_value()) { velocity_factor_interface_.set( - path.points, getEgoPose(), stop_pose_.value(), VelocityFactor::APPROACHING, "stop"); + path.points, getEgoPose(), stop_pose_.value().pose, VelocityFactor::APPROACHING, "stop"); return; } @@ -565,7 +571,7 @@ class SceneModuleInterface } velocity_factor_interface_.set( - path.points, getEgoPose(), slow_pose_.value(), VelocityFactor::APPROACHING, "slow down"); + path.points, getEgoPose(), slow_pose_.value().pose, VelocityFactor::APPROACHING, "slow down"); } void setDrivableLanes(const std::vector & drivable_lanes); @@ -625,11 +631,11 @@ class SceneModuleInterface mutable VelocityFactorInterface velocity_factor_interface_; - mutable std::optional stop_pose_{std::nullopt}; + mutable PoseWithDetailOpt stop_pose_{std::nullopt}; - mutable std::optional slow_pose_{std::nullopt}; + mutable PoseWithDetailOpt slow_pose_{std::nullopt}; - mutable std::optional dead_pose_{std::nullopt}; + mutable PoseWithDetailOpt dead_pose_{std::nullopt}; mutable MarkerArray info_marker_; diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index e199309dea8bb..73b133952935b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -16,6 +16,7 @@ #ifndef AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__SCENE_MODULE_MANAGER_INTERFACE_HPP_ #define AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__INTERFACE__SCENE_MODULE_MANAGER_INTERFACE_HPP_ +#include "autoware/behavior_path_planner_common/data_manager.hpp" #include "autoware/behavior_path_planner_common/interface/scene_module_interface.hpp" #include "autoware/universe_utils/ros/parameter.hpp" @@ -34,7 +35,6 @@ #include #include #include - namespace autoware::behavior_path_planner { @@ -160,25 +160,23 @@ class SceneModuleManagerInterface continue; } - const auto opt_stop_pose = m.lock()->getStopPose(); - if (!!opt_stop_pose) { - const auto virtual_wall = createStopVirtualWallMarker( - opt_stop_pose.value(), m.lock()->name(), rclcpp::Clock().now(), marker_id); - appendMarkerArray(virtual_wall, &markers); - } - - const auto opt_slow_pose = m.lock()->getSlowPose(); - if (!!opt_slow_pose) { - const auto virtual_wall = createSlowDownVirtualWallMarker( - opt_slow_pose.value(), m.lock()->name(), rclcpp::Clock().now(), marker_id); - appendMarkerArray(virtual_wall, &markers); - } - - const auto opt_dead_pose = m.lock()->getDeadPose(); - if (!!opt_dead_pose) { - const auto virtual_wall = createDeadLineVirtualWallMarker( - opt_dead_pose.value(), m.lock()->name(), rclcpp::Clock().now(), marker_id); - appendMarkerArray(virtual_wall, &markers); + const std::vector>> + pose_and_func_vec = { + {m.lock()->getStopPose(), createStopVirtualWallMarker}, + {m.lock()->getSlowPose(), createSlowDownVirtualWallMarker}, + {m.lock()->getDeadPose(), createDeadLineVirtualWallMarker}}; + + for (const auto & [opt_pose, create_virtual_wall] : pose_and_func_vec) { + if (!!opt_pose) { + const auto detail = opt_pose.value().detail; + const auto text = m.lock()->name() + (detail.empty() ? "" : " (" + detail + ")"); + const auto virtual_wall = create_virtual_wall( + opt_pose.value().pose, text, rclcpp::Clock().now(), marker_id, 0.0, "", true); + appendMarkerArray(virtual_wall, &markers); + } } const auto module_specific_wall = m.lock()->getModuleVirtualWall(); diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/utils.hpp index d34bfeb535f19..42329883de692 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/utils.hpp @@ -70,8 +70,7 @@ std::pair getPairsTerminalVelocityAndAccel( std::optional generateFeasibleStopPath( PathWithLaneId & current_path, std::shared_ptr planner_data, - std::optional & stop_pose, const double maximum_deceleration, - const double maximum_jerk); + PoseWithDetailOpt & stop_pose, const double maximum_deceleration, const double maximum_jerk); /** * @brief calculate end arc length to generate reference path considering the goal position diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp index 18dee25919f98..5802f111848b4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -121,8 +121,7 @@ std::pair getPairsTerminalVelocityAndAccel( std::optional generateFeasibleStopPath( PathWithLaneId & current_path, std::shared_ptr planner_data, - std::optional & stop_pose, const double maximum_deceleration, - const double maximum_jerk) + PoseWithDetailOpt & stop_pose, const double maximum_deceleration, const double maximum_jerk) { if (current_path.points.empty()) { return {}; @@ -146,7 +145,7 @@ std::optional generateFeasibleStopPath( return {}; } - stop_pose = current_path.points.at(*stop_idx).point.pose; + stop_pose = PoseWithDetail(current_path.points.at(*stop_idx).point.pose); return current_path; } diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_parking_departure_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_parking_departure_utils.cpp index 2b43cdaebd14d..cefa9151dd604 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_parking_departure_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_parking_departure_utils.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "autoware/behavior_path_planner_common/data_manager.hpp" #include "autoware/behavior_path_planner_common/utils/parking_departure/utils.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -222,7 +223,7 @@ TEST(BehaviorPathPlanningParkingDepartureUtil, generateFeasibleStopPath) data->self_acceleration = accel_with_covariance; auto planner_data = std::static_pointer_cast(data); - std::optional stop_pose; + autoware::behavior_path_planner::PoseWithDetailOpt stop_pose{std::nullopt}; // condition: empty path PathWithLaneId path; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp index bb70ae2638056..47eecb54e2b2a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/include/autoware/behavior_path_start_planner_module/start_planner_module.hpp @@ -70,7 +70,7 @@ struct PullOutStatus Pose pull_out_start_pose{}; bool prev_is_safe_dynamic_objects{false}; std::shared_ptr prev_stop_path_after_approval{nullptr}; - std::optional stop_pose{std::nullopt}; + PoseWithDetailOpt stop_pose{std::nullopt}; //! record the first time when ego started forward-driving (maybe after backward driving //! completion) in AUTONOMOUS operation mode std::optional first_engaged_and_driving_forward_time{std::nullopt}; diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp index 20cac638cebbd..c223390e454d1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp @@ -634,7 +634,7 @@ bool StartPlannerModule::isExecutionReady() const }(); if (!is_safe) { - stop_pose_ = planner_data_->self_odometry->pose.pose; + stop_pose_ = PoseWithDetail(planner_data_->self_odometry->pose.pose); } return is_safe; diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp index 9509b9954304d..fe4a6d557da01 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp @@ -168,7 +168,7 @@ lanelet::ConstLanelets getExtendLanes( */ void insertDecelPoint( const Point & p_src, const double offset, const double velocity, PathWithLaneId & path, - std::optional & p_out); + PoseWithDetailOpt & p_out); /** * @brief update envelope polygon based on object position reliability. diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp index 76bfa621ac0e4..be4ce4a125c68 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp @@ -736,12 +736,11 @@ void StaticObstacleAvoidanceModule::fillDebugData( const auto prepare_distance = helper_->getNominalPrepareDistance(); const auto total_avoid_distance = prepare_distance + avoidance_distance + constant_distance; - dead_pose_ = autoware::motion_utils::calcLongitudinalOffsetPose( + const auto dead_pose_opt = autoware::motion_utils::calcLongitudinalOffsetPose( data.reference_path.points, getEgoPosition(), o_front.longitudinal - total_avoid_distance); - - if (!dead_pose_) { - dead_pose_ = getPose(data.reference_path.points.front()); - } + dead_pose_ = dead_pose_opt.has_value() + ? PoseWithDetail(dead_pose_opt.value()) + : PoseWithDetail(getPose(data.reference_path.points.front())); } void StaticObstacleAvoidanceModule::updateEgoBehavior( @@ -1949,8 +1948,10 @@ void StaticObstacleAvoidanceModule::insertPrepareVelocity(ShiftedPath & shifted_ shifted_path.path.points.at(i).point.longitudinal_velocity_mps = std::min(v_original, v_insert); } - slow_pose_ = autoware::motion_utils::calcLongitudinalOffsetPose( + const auto slow_pose_opt = autoware::motion_utils::calcLongitudinalOffsetPose( shifted_path.path.points, start_idx, distance_to_object); + slow_pose_ = slow_pose_opt.has_value() ? PoseWithDetailOpt(PoseWithDetail(slow_pose_opt.value())) + : std::nullopt; } void StaticObstacleAvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifted_path) const @@ -1997,8 +1998,10 @@ void StaticObstacleAvoidanceModule::insertAvoidanceVelocity(ShiftedPath & shifte shifted_path.path.points.at(i).point.longitudinal_velocity_mps = std::min(v_original, v_target); } - slow_pose_ = autoware::motion_utils::calcLongitudinalOffsetPose( + const auto slow_pose_opt = autoware::motion_utils::calcLongitudinalOffsetPose( shifted_path.path.points, start_idx, distance_to_accel_end_point); + slow_pose_ = slow_pose_opt.has_value() ? PoseWithDetailOpt(PoseWithDetail(slow_pose_opt.value())) + : std::nullopt; } std::shared_ptr StaticObstacleAvoidanceModule::get_debug_msg_array() const diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp index c3d494c8ffe5d..8c09cd2e011f9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/utils.cpp @@ -1512,7 +1512,7 @@ lanelet::ConstLanelets getExtendLanes( void insertDecelPoint( const Point & p_src, const double offset, const double velocity, PathWithLaneId & path, - std::optional & p_out) + PoseWithDetailOpt & p_out) { const auto decel_point = autoware::motion_utils::calcLongitudinalOffsetPoint(path.points, p_src, offset); @@ -1541,7 +1541,7 @@ void insertDecelPoint( insertVelocity(path, velocity); - p_out = getPose(path.points.at(insert_idx.value())); + p_out = PoseWithDetail(getPose(path.points.at(insert_idx.value()))); } void fillObjectEnvelopePolygon( diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp index 6911be800bdc2..ffccd2d64c189 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/test/test_utils.cpp @@ -823,7 +823,7 @@ TEST(TestUtils, insertDecelPoint) constexpr double offset = 100.0; constexpr double velocity = 1.0; - std::optional p_out{std::nullopt}; + PoseWithDetailOpt p_out{std::nullopt}; insertDecelPoint(ego_position, offset, velocity, path, p_out); EXPECT_FALSE(p_out.has_value()); @@ -841,13 +841,13 @@ TEST(TestUtils, insertDecelPoint) constexpr double offset = 3.0; constexpr double velocity = 1.0; - std::optional p_out{std::nullopt}; + PoseWithDetailOpt p_out{std::nullopt}; insertDecelPoint(ego_position, offset, velocity, path, p_out); ASSERT_TRUE(p_out.has_value()); - EXPECT_DOUBLE_EQ(p_out.value().position.x, 6.5); - EXPECT_DOUBLE_EQ(p_out.value().position.y, 0.0); - EXPECT_DOUBLE_EQ(p_out.value().position.z, 0.0); + EXPECT_DOUBLE_EQ(p_out.value().pose.position.x, 6.5); + EXPECT_DOUBLE_EQ(p_out.value().pose.position.y, 0.0); + EXPECT_DOUBLE_EQ(p_out.value().pose.position.z, 0.0); for (size_t i = 7; i < path.points.size(); i++) { EXPECT_DOUBLE_EQ(path.points.at(i).point.longitudinal_velocity_mps, 1.0); } From 6fa1a723af4307f70964f79bc0a8705ebd9c7ccf Mon Sep 17 00:00:00 2001 From: Felix F Xu <84662027+felixf4xu@users.noreply.github.com> Date: Wed, 11 Dec 2024 00:55:31 +0800 Subject: [PATCH 263/273] build(behavior_path_planner_common): fix #include (#6297) Signed-off-by: Felix Xavier --- .../autoware/behavior_path_planner_common/data_manager.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp index 31d1f0072fe5c..749d732aecd00 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/data_manager.hpp @@ -23,8 +23,8 @@ #include #include #include -#include -#include +#include +#include #include #include From 386d2af4ac25e41ff76e757746dc45ad4bf40f8e Mon Sep 17 00:00:00 2001 From: Yoshi Ri Date: Wed, 11 Dec 2024 09:59:18 +0900 Subject: [PATCH 264/273] feat: remove max rois limit in the image projection based fusion (#9596) feat: remove max rois limit Signed-off-by: yoshiri --- .../src/fusion_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 60406652310dd..6c575752b52e5 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -57,8 +57,8 @@ FusionNode::FusionNode( } if (rois_number_ > 8) { RCLCPP_WARN( - this->get_logger(), "maximum rois_number is 8. current rois_number is %zu", rois_number_); - rois_number_ = 8; + this->get_logger(), + "Current rois_number is %zu. Large rois number may cause performance issue.", rois_number_); } // Set parameters From 01944efd391fa85f16022571e40a63a96efae2f3 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Wed, 11 Dec 2024 10:05:23 +0900 Subject: [PATCH 265/273] fix(lidar_centerpoint): non-maximum suppression target decision logic (#9595) * refactor(lidar_centerpoint): optimize non-maximum suppression search distance calculation Signed-off-by: Taekjin LEE * feat(lidar_centerpoint): do not suppress if one side of the object is pedestrian Signed-off-by: Taekjin LEE * style(pre-commit): autofix * refactor(lidar_centerpoint): remove unused variables Signed-off-by: Taekjin LEE * refactor: remove unused variables Signed-off-by: Taekjin LEE fix: implement non-maximum suppression logic to the transfusion Signed-off-by: Taekjin LEE refactor: remove unused parameter iou_nms_target_class_names Signed-off-by: Taekjin LEE Revert "fix: implement non-maximum suppression logic to the transfusion" This reverts commit b8017fc366ec7d67234445ef5869f8beca9b6f45. fix: revert transfusion modification --------- Signed-off-by: Taekjin LEE Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../config/pointpainting.param.yaml | 1 - .../docs/pointpainting-fusion.md | 1 - .../schema/pointpainting.schema.json | 6 --- .../src/pointpainting_fusion/node.cpp | 3 -- .../autoware_lidar_centerpoint/README.md | 2 - .../config/centerpoint.param.yaml | 1 - .../config/centerpoint_sigma.param.yaml | 1 - .../config/centerpoint_tiny.param.yaml | 1 - .../postprocess/non_maximum_suppression.hpp | 29 +------------- .../postprocess/non_maximum_suppression.cpp | 40 +++++++------------ .../schema/centerpoint.schemal.json | 6 --- .../autoware_lidar_centerpoint/src/node.cpp | 3 -- .../test/test_nms.cpp | 2 - 13 files changed, 17 insertions(+), 79 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml b/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml index 9227e4fa9319a..5448dd48dc456 100644 --- a/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml @@ -9,7 +9,6 @@ post_process_params: # post-process params circle_nms_dist_threshold: 0.3 - iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 score_threshold: 0.35 diff --git a/perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md b/perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md index e04b0f48398cb..92f62443918c0 100644 --- a/perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md +++ b/perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md @@ -43,7 +43,6 @@ The lidar points are projected onto the output of an image-only 2d object detect | `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` | | `post_process_params.score_threshold` | double | `0.4` | detected objects with score less than threshold are ignored | | `post_process_params.yaw_norm_thresholds` | list[double] | [0.3, 0.3, 0.3, 0.3, 0.0] | An array of distance threshold values of norm of yaw [rad]. | -| `post_process_params.iou_nms_target_class_names` | list[string] | ["CAR"] | An array of class names to be target in NMS. | | `post_process_params.iou_nms_search_distance_2d` | double | 10.0 | A maximum distance value to search the nearest objects. | | `post_process_params.iou_nms_threshold` | double | 0.1 | A threshold value of NMS using IoU score. | | `post_process_params.has_twist` | boolean | false | Indicates whether the model outputs twist value. | diff --git a/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json b/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json index 57d8bc500f3c6..ab52ac0fcdf2c 100644 --- a/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json +++ b/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json @@ -46,12 +46,6 @@ "minimum": 0.0, "maximum": 1.0 }, - "iou_nms_target_class_names": { - "type": "array", - "description": "An array of class names to be target in NMS.", - "default": ["CAR"], - "uniqueItems": true - }, "iou_nms_search_distance_2d": { "type": "number", "description": "A maximum distance value to search the nearest objects.", diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 4e0f88e2134ac..d4601e26dda46 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -171,9 +171,6 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt { autoware::lidar_centerpoint::NMSParams p; - p.nms_type_ = autoware::lidar_centerpoint::NMS_TYPE::IoU_BEV; - p.target_class_names_ = this->declare_parameter>( - "post_process_params.iou_nms_target_class_names"); p.search_distance_2d_ = this->declare_parameter("post_process_params.iou_nms_search_distance_2d"); p.iou_threshold_ = this->declare_parameter("post_process_params.iou_nms_threshold"); diff --git a/perception/autoware_lidar_centerpoint/README.md b/perception/autoware_lidar_centerpoint/README.md index 471712a637dec..06ded16d5fd40 100644 --- a/perception/autoware_lidar_centerpoint/README.md +++ b/perception/autoware_lidar_centerpoint/README.md @@ -56,7 +56,6 @@ Note that these parameters are associated with ONNX file, predefined during the | `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` | | `post_process_params.score_threshold` | double | `0.4` | detected objects with score less than threshold are ignored | | `post_process_params.yaw_norm_thresholds` | list[double] | [0.3, 0.3, 0.3, 0.3, 0.0] | An array of distance threshold values of norm of yaw [rad]. | -| `post_process_params.iou_nms_target_class_names` | list[string] | - | target classes for IoU-based Non Maximum Suppression | | `post_process_params.iou_nms_search_distance_2d` | double | - | If two objects are farther than the value, NMS isn't applied. | | `post_process_params.iou_nms_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression | | `post_process_params.has_twist` | boolean | false | Indicates whether the model outputs twist value. | @@ -267,7 +266,6 @@ point_cloud_range, point_feature_size, voxel_size, etc. according to the trainin encoder_in_feature_size: 9 # post-process params circle_nms_dist_threshold: 0.5 - iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml index 53d77e8d1c42c..d2f6d3bb3ab6c 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml @@ -10,7 +10,6 @@ post_process_params: # post-process params circle_nms_dist_threshold: 0.5 - iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 score_threshold: 0.35 diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml index bd5fc5f3567a5..f4a5d59c3c06f 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml @@ -11,7 +11,6 @@ post_process_params: # post-process params circle_nms_dist_threshold: 0.5 - iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml index 53d77e8d1c42c..d2f6d3bb3ab6c 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml @@ -10,7 +10,6 @@ post_process_params: # post-process params circle_nms_dist_threshold: 0.5 - iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 score_threshold: 0.35 diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp index 57abd053af718..74bc5c2f57deb 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp @@ -28,36 +28,12 @@ namespace autoware::lidar_centerpoint { using autoware_perception_msgs::msg::DetectedObject; -// TODO(yukke42): now only support IoU_BEV -enum class NMS_TYPE { - IoU_BEV - // IoU_3D - // Distance_2D - // Distance_3D -}; - struct NMSParams { - NMS_TYPE nms_type_{}; - std::vector target_class_names_{}; double search_distance_2d_{}; double iou_threshold_{}; - // double distance_threshold_{}; }; -std::vector classNamesToBooleanMask(const std::vector & class_names) -{ - std::vector mask; - constexpr std::size_t num_object_classification = 8; - mask.resize(num_object_classification); - for (const auto & class_name : class_names) { - const auto semantic_type = getSemanticType(class_name); - mask.at(semantic_type) = true; - } - - return mask; -} - class NonMaximumSuppression { public: @@ -66,14 +42,13 @@ class NonMaximumSuppression std::vector apply(const std::vector &); private: - bool isTargetLabel(const std::uint8_t); - bool isTargetPairObject(const DetectedObject &, const DetectedObject &); Eigen::MatrixXd generateIoUMatrix(const std::vector &); NMSParams params_{}; - std::vector target_class_mask_{}; + + double search_distance_2d_sq_{}; }; } // namespace autoware::lidar_centerpoint diff --git a/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp b/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp index 9764d20628f24..dbc6924f6fd25 100644 --- a/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp @@ -22,6 +22,7 @@ namespace autoware::lidar_centerpoint { +using Label = autoware_perception_msgs::msg::ObjectClassification; void NonMaximumSuppression::setParameters(const NMSParams & params) { @@ -29,15 +30,7 @@ void NonMaximumSuppression::setParameters(const NMSParams & params) assert(params.iou_threshold_ >= 0.0 && params.iou_threshold_ <= 1.0); params_ = params; - target_class_mask_ = classNamesToBooleanMask(params.target_class_names_); -} - -bool NonMaximumSuppression::isTargetLabel(const uint8_t label) -{ - if (label >= target_class_mask_.size()) { - return false; - } - return target_class_mask_.at(label); + search_distance_2d_sq_ = params.search_distance_2d_ * params.search_distance_2d_; } bool NonMaximumSuppression::isTargetPairObject( @@ -48,15 +41,15 @@ bool NonMaximumSuppression::isTargetPairObject( const auto label2 = autoware::object_recognition_utils::getHighestProbLabel(object2.classification); - if (isTargetLabel(label1) && isTargetLabel(label2)) { - return true; + // if labels are not the same, and one of them is pedestrian, do not suppress + if (label1 != label2 && (label1 == Label::PEDESTRIAN || label2 == Label::PEDESTRIAN)) { + return false; } - const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_; const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d( autoware::object_recognition_utils::getPose(object1), autoware::object_recognition_utils::getPose(object2)); - return sqr_dist_2d <= search_sqr_dist_2d; + return sqr_dist_2d <= search_distance_2d_sq_; } Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix( @@ -73,14 +66,12 @@ Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix( continue; } - if (params_.nms_type_ == NMS_TYPE::IoU_BEV) { - const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj); - triangular_matrix(target_i, source_i) = iou; - // NOTE: If the target object has any objects with iou > iou_threshold, it - // will be suppressed regardless of later results. - if (iou > params_.iou_threshold_) { - break; - } + const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj); + triangular_matrix(target_i, source_i) = iou; + // NOTE: If the target object has any objects with iou > iou_threshold, it + // will be suppressed regardless of later results. + if (iou > params_.iou_threshold_) { + break; } } } @@ -97,10 +88,9 @@ std::vector NonMaximumSuppression::apply( output_objects.reserve(input_objects.size()); for (std::size_t i = 0; i < input_objects.size(); ++i) { const auto value = iou_matrix.row(i).maxCoeff(); - if (params_.nms_type_ == NMS_TYPE::IoU_BEV) { - if (value <= params_.iou_threshold_) { - output_objects.emplace_back(input_objects.at(i)); - } + + if (value <= params_.iou_threshold_) { + output_objects.emplace_back(input_objects.at(i)); } } diff --git a/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json b/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json index c3268f0e90d9b..f2c12b7588f9b 100644 --- a/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json +++ b/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json @@ -42,12 +42,6 @@ "minimum": 0.0, "maximum": 1.0 }, - "iou_nms_target_class_names": { - "type": "array", - "description": "An array of class names to be target in NMS.", - "default": ["CAR"], - "uniqueItems": true - }, "iou_nms_search_distance_2d": { "type": "number", "description": "A maximum distance value to search the nearest objects.", diff --git a/perception/autoware_lidar_centerpoint/src/node.cpp b/perception/autoware_lidar_centerpoint/src/node.cpp index 5b92e5c811a23..59acceeac54d6 100644 --- a/perception/autoware_lidar_centerpoint/src/node.cpp +++ b/perception/autoware_lidar_centerpoint/src/node.cpp @@ -80,9 +80,6 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti { NMSParams p; - p.nms_type_ = NMS_TYPE::IoU_BEV; - p.target_class_names_ = this->declare_parameter>( - "post_process_params.iou_nms_target_class_names"); p.search_distance_2d_ = this->declare_parameter("post_process_params.iou_nms_search_distance_2d"); p.iou_threshold_ = this->declare_parameter("post_process_params.iou_nms_threshold"); diff --git a/perception/autoware_lidar_centerpoint/test/test_nms.cpp b/perception/autoware_lidar_centerpoint/test/test_nms.cpp index fd9e78b0c6585..9a2217f7af0b4 100644 --- a/perception/autoware_lidar_centerpoint/test/test_nms.cpp +++ b/perception/autoware_lidar_centerpoint/test/test_nms.cpp @@ -24,8 +24,6 @@ TEST(NonMaximumSuppressionTest, Apply) autoware::lidar_centerpoint::NMSParams params; params.search_distance_2d_ = 1.0; params.iou_threshold_ = 0.2; - params.nms_type_ = autoware::lidar_centerpoint::NMS_TYPE::IoU_BEV; - params.target_class_names_ = {"CAR"}; nms.setParameters(params); std::vector input_objects(4); From da5284cb89cb4e4263ead39d8a083534032fa848 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Wed, 11 Dec 2024 15:59:20 +0900 Subject: [PATCH 266/273] fix(autoware_lidar_transfusion): non-maximum suppression target decision logic (#9612) fix: non-maximum suppression target decision logic Signed-off-by: Taekjin LEE --- .../config/transfusion.param.yaml | 1 - .../postprocess/non_maximum_suppression.hpp | 28 +------------ .../postprocess/non_maximum_suppression.cpp | 40 +++++++------------ .../schema/transfusion.schema.dummy.json | 10 ----- .../src/lidar_transfusion_node.cpp | 3 -- .../test/test_nms.cpp | 2 - 6 files changed, 17 insertions(+), 67 deletions(-) diff --git a/perception/autoware_lidar_transfusion/config/transfusion.param.yaml b/perception/autoware_lidar_transfusion/config/transfusion.param.yaml index 47eaa800e62fc..979f8b9cc09e3 100644 --- a/perception/autoware_lidar_transfusion/config/transfusion.param.yaml +++ b/perception/autoware_lidar_transfusion/config/transfusion.param.yaml @@ -10,7 +10,6 @@ densification_world_frame_id: map # post-process params circle_nms_dist_threshold: 0.5 - iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # refers to the class_names diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/postprocess/non_maximum_suppression.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/postprocess/non_maximum_suppression.hpp index 9f07d2448fcae..26c4e324781d0 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/postprocess/non_maximum_suppression.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/postprocess/non_maximum_suppression.hpp @@ -28,35 +28,12 @@ namespace autoware::lidar_transfusion { using autoware_perception_msgs::msg::DetectedObject; -enum class NMS_TYPE { - IoU_BEV - // IoU_3D - // Distance_2D - // Distance_3D -}; - struct NMSParams { - NMS_TYPE nms_type_{}; - std::vector target_class_names_{}; double search_distance_2d_{}; double iou_threshold_{}; - // double distance_threshold_{}; }; -std::vector classNamesToBooleanMask(const std::vector & class_names) -{ - std::vector mask; - constexpr std::size_t num_object_classification = 8; - mask.resize(num_object_classification); - for (const auto & class_name : class_names) { - const auto semantic_type = getSemanticType(class_name); - mask.at(semantic_type) = true; - } - - return mask; -} - class NonMaximumSuppression { public: @@ -65,14 +42,13 @@ class NonMaximumSuppression std::vector apply(const std::vector &); private: - bool isTargetLabel(const std::uint8_t); - bool isTargetPairObject(const DetectedObject &, const DetectedObject &); Eigen::MatrixXd generateIoUMatrix(const std::vector &); NMSParams params_{}; - std::vector target_class_mask_{}; + + double search_distance_2d_sq_{}; }; } // namespace autoware::lidar_transfusion diff --git a/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp b/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp index 1a288d1b0fd44..003358dc6b431 100644 --- a/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp @@ -22,6 +22,7 @@ namespace autoware::lidar_transfusion { +using Label = autoware_perception_msgs::msg::ObjectClassification; void NonMaximumSuppression::setParameters(const NMSParams & params) { @@ -29,15 +30,7 @@ void NonMaximumSuppression::setParameters(const NMSParams & params) assert(params.iou_threshold_ >= 0.0 && params.iou_threshold_ <= 1.0); params_ = params; - target_class_mask_ = classNamesToBooleanMask(params.target_class_names_); -} - -bool NonMaximumSuppression::isTargetLabel(const uint8_t label) -{ - if (label >= target_class_mask_.size()) { - return false; - } - return target_class_mask_.at(label); + search_distance_2d_sq_ = params.search_distance_2d_ * params.search_distance_2d_; } bool NonMaximumSuppression::isTargetPairObject( @@ -48,15 +41,15 @@ bool NonMaximumSuppression::isTargetPairObject( const auto label2 = autoware::object_recognition_utils::getHighestProbLabel(object2.classification); - if (isTargetLabel(label1) && isTargetLabel(label2)) { - return true; + // if labels are not the same, and one of them is pedestrian, do not suppress + if (label1 != label2 && (label1 == Label::PEDESTRIAN || label2 == Label::PEDESTRIAN)) { + return false; } - const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_; const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d( autoware::object_recognition_utils::getPose(object1), autoware::object_recognition_utils::getPose(object2)); - return sqr_dist_2d <= search_sqr_dist_2d; + return sqr_dist_2d <= search_distance_2d_sq_; } Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix( @@ -73,14 +66,12 @@ Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix( continue; } - if (params_.nms_type_ == NMS_TYPE::IoU_BEV) { - const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj); - triangular_matrix(target_i, source_i) = iou; - // NOTE: If the target object has any objects with iou > iou_threshold, it - // will be suppressed regardless of later results. - if (iou > params_.iou_threshold_) { - break; - } + const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj); + triangular_matrix(target_i, source_i) = iou; + // NOTE: If the target object has any objects with iou > iou_threshold, it + // will be suppressed regardless of later results. + if (iou > params_.iou_threshold_) { + break; } } } @@ -97,10 +88,9 @@ std::vector NonMaximumSuppression::apply( output_objects.reserve(input_objects.size()); for (std::size_t i = 0; i < input_objects.size(); ++i) { const auto value = iou_matrix.row(i).maxCoeff(); - if (params_.nms_type_ == NMS_TYPE::IoU_BEV) { - if (value <= params_.iou_threshold_) { - output_objects.emplace_back(input_objects.at(i)); - } + + if (value <= params_.iou_threshold_) { + output_objects.emplace_back(input_objects.at(i)); } } diff --git a/perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json b/perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json index 6d9029f7e6806..739c641b7cefb 100644 --- a/perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json +++ b/perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json @@ -48,15 +48,6 @@ "default": 0.5, "minimum": 0.0 }, - "iou_nms_target_class_names": { - "type": "array", - "items": { - "type": "string" - }, - "description": "An array of class names to be target in NMS.", - "default": ["CAR"], - "uniqueItems": true - }, "iou_nms_search_distance_2d": { "type": "number", "description": "A maximum distance value to search the nearest objects.", @@ -95,7 +86,6 @@ "densification_num_past_frames", "densification_world_frame_id", "circle_nms_dist_threshold", - "iou_nms_target_class_names", "iou_nms_search_distance_2d", "iou_nms_threshold", "yaw_norm_thresholds", diff --git a/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp b/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp index c75a5f434aeed..8bb70a821621f 100644 --- a/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp +++ b/perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp @@ -65,9 +65,6 @@ LidarTransfusionNode::LidarTransfusionNode(const rclcpp::NodeOptions & options) static_cast(this->declare_parameter("circle_nms_dist_threshold", descriptor)); { // IoU NMS NMSParams p; - p.nms_type_ = NMS_TYPE::IoU_BEV; - p.target_class_names_ = - this->declare_parameter>("iou_nms_target_class_names", descriptor); p.search_distance_2d_ = this->declare_parameter("iou_nms_search_distance_2d", descriptor); p.iou_threshold_ = this->declare_parameter("iou_nms_threshold", descriptor); diff --git a/perception/autoware_lidar_transfusion/test/test_nms.cpp b/perception/autoware_lidar_transfusion/test/test_nms.cpp index 5449f61aa2284..dcb523abd96d8 100644 --- a/perception/autoware_lidar_transfusion/test/test_nms.cpp +++ b/perception/autoware_lidar_transfusion/test/test_nms.cpp @@ -24,8 +24,6 @@ TEST(NonMaximumSuppressionTest, Apply) autoware::lidar_transfusion::NMSParams params; params.search_distance_2d_ = 1.0; params.iou_threshold_ = 0.2; - params.nms_type_ = autoware::lidar_transfusion::NMS_TYPE::IoU_BEV; - params.target_class_names_ = {"CAR"}; nms.setParameters(params); std::vector input_objects(4); From 26b1ab6fd4b21dfd41fb4b5b9ebb7976f5b10ca8 Mon Sep 17 00:00:00 2001 From: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> Date: Wed, 11 Dec 2024 18:16:28 +0900 Subject: [PATCH 267/273] refactor(obstacle_cruise_planner)!: refactor rviz and terminal info (#9594) Signed-off-by: yuki-takagi-66 --- .../obstacle_cruise_planner/common_structs.hpp | 7 +++++-- .../autoware/obstacle_cruise_planner/node.hpp | 3 +++ .../autoware_obstacle_cruise_planner/package.xml | 1 + .../autoware_obstacle_cruise_planner/src/node.cpp | 14 +++++++++----- .../src/pid_based_planner/pid_based_planner.cpp | 5 ++++- .../autoware_obstacle_cruise_planner/src/utils.cpp | 2 +- 6 files changed, 23 insertions(+), 9 deletions(-) diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp index 7bd4d37ba5797..8abff415e47df 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp @@ -169,12 +169,15 @@ struct CruiseObstacle : public TargetObstacleInterface CruiseObstacle( const std::string & arg_uuid, const rclcpp::Time & arg_stamp, const geometry_msgs::msg::Pose & arg_pose, const double arg_lon_velocity, - const double arg_lat_velocity, const std::vector & arg_collision_points) + const double arg_lat_velocity, const std::vector & arg_collision_points, + bool arg_is_yield_obstacle = false) : TargetObstacleInterface(arg_uuid, arg_stamp, arg_pose, arg_lon_velocity, arg_lat_velocity), - collision_points(arg_collision_points) + collision_points(arg_collision_points), + is_yield_obstacle(arg_is_yield_obstacle) { } std::vector collision_points; // time-series collision points + bool is_yield_obstacle; }; struct SlowDownObstacle : public TargetObstacleInterface diff --git a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp index 629dba73e85dc..6a106776e48b5 100644 --- a/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp +++ b/planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp @@ -24,6 +24,7 @@ #include "autoware/universe_utils/ros/polling_subscriber.hpp" #include "autoware/universe_utils/system/stop_watch.hpp" +#include #include #include @@ -180,6 +181,8 @@ class ObstacleCruisePlannerNode : public rclcpp::Node this, "~/input/pointcloud"}; autoware::universe_utils::InterProcessPollingSubscriber acc_sub_{ this, "~/input/acceleration"}; + autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface + objects_of_interest_marker_interface_{this, "obstacle_cruise_planner"}; std::unique_ptr tf_buffer_; std::shared_ptr tf_listener_{nullptr}; diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index df760ee59de37..75405c3aded2a 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -23,6 +23,7 @@ autoware_lanelet2_extension autoware_motion_utils autoware_object_recognition_utils + autoware_objects_of_interest_marker_interface autoware_osqp_interface autoware_perception_msgs autoware_planning_msgs diff --git a/planning/autoware_obstacle_cruise_planner/src/node.cpp b/planning/autoware_obstacle_cruise_planner/src/node.cpp index 8275f2a1cd7d4..6931ff58e8457 100644 --- a/planning/autoware_obstacle_cruise_planner/src/node.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/node.cpp @@ -515,10 +515,9 @@ ObstacleCruisePlannerNode::ObstacleCruisePlannerNode(const rclcpp::NodeOptions & // debug publisher debug_calculation_time_pub_ = create_publisher("~/debug/processing_time_ms", 1); - debug_cruise_wall_marker_pub_ = create_publisher("~/debug/cruise/virtual_wall", 1); - debug_stop_wall_marker_pub_ = create_publisher("~/virtual_wall", 1); - debug_slow_down_wall_marker_pub_ = - create_publisher("~/debug/slow_down/virtual_wall", 1); + debug_cruise_wall_marker_pub_ = create_publisher("~/virtual_wall/cruise", 1); + debug_stop_wall_marker_pub_ = create_publisher("~/virtual_wall/stop", 1); + debug_slow_down_wall_marker_pub_ = create_publisher("~/virtual_wall/slow_down", 1); debug_marker_pub_ = create_publisher("~/debug/marker", 1); debug_stop_planning_info_pub_ = create_publisher("~/debug/stop_planning_info", 1); @@ -729,6 +728,7 @@ void ObstacleCruisePlannerNode::onTrajectory(const Trajectory::ConstSharedPtr ms planner_ptr_->publishMetrics(now()); publishDebugMarker(); publishDebugInfo(); + objects_of_interest_marker_interface_.publishMarkerArray(); // 9. Publish and print calculation time const double calculation_time = stop_watch_.toc(__func__); @@ -1385,7 +1385,8 @@ std::optional ObstacleCruisePlannerNode::createYieldCruiseObstac obstacle.pose, obstacle.longitudinal_velocity, obstacle.approach_velocity, - collision_points.value()}; + collision_points.value(), + true}; } std::optional> ObstacleCruisePlannerNode::findYieldCruiseObstacles( @@ -1456,6 +1457,9 @@ std::optional> ObstacleCruisePlannerNode::findYieldC const auto yield_obstacle = createYieldCruiseObstacle(moving_obstacle, traj_points); if (yield_obstacle) { yield_obstacles.push_back(*yield_obstacle); + using autoware::objects_of_interest_marker_interface::ColorName; + objects_of_interest_marker_interface_.insertObjectData( + stopped_obstacle.pose, stopped_obstacle.shape, ColorName::RED); } } } diff --git a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp index f8982ed3fec2a..544597f05ff75 100644 --- a/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp @@ -320,8 +320,11 @@ std::vector PIDBasedPlanner::planCruise( const size_t wall_idx = obstacle_cruise_utils::getIndexWithLongitudinalOffset( stop_traj_points, dist_to_rss_wall, ego_idx); + const std::string wall_reason_string = cruise_obstacle_info->obstacle.is_yield_obstacle + ? "obstacle cruise (yield)" + : "obstacle cruise"; auto markers = autoware::motion_utils::createSlowDownVirtualWallMarker( - stop_traj_points.at(wall_idx).pose, "obstacle cruise", planner_data.current_time, 0); + stop_traj_points.at(wall_idx).pose, wall_reason_string, planner_data.current_time, 0); // NOTE: use a different color from slow down one to visualize cruise and slow down // separately. markers.markers.front().color = diff --git a/planning/autoware_obstacle_cruise_planner/src/utils.cpp b/planning/autoware_obstacle_cruise_planner/src/utils.cpp index dd4373c115fe0..82f4e6978181f 100644 --- a/planning/autoware_obstacle_cruise_planner/src/utils.cpp +++ b/planning/autoware_obstacle_cruise_planner/src/utils.cpp @@ -92,7 +92,7 @@ PoseWithStamp getCurrentObjectPose( getCurrentObjectPoseFromPredictedPaths(predicted_paths, obj_base_time, current_time); if (!interpolated_pose) { - RCLCPP_WARN( + RCLCPP_DEBUG( rclcpp::get_logger("ObstacleCruisePlanner"), "Failed to find the interpolated obstacle pose"); return PoseWithStamp{obj_base_time, pose}; } From 778c074ec39f52042dc42e2860e392da180ec893 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Wed, 11 Dec 2024 19:55:17 +0900 Subject: [PATCH 268/273] chore(planning_test_manager): update owner (#9620) Signed-off-by: Mamoru Sobue --- planning/autoware_planning_test_manager/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index ec22d871013d3..1b38944f545bc 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -6,6 +6,7 @@ ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara Takamasa Horibe + Mamoru Sobue Apache License 2.0 Kyoichi Sugahara From 53aaf0f2764daf6831f64bc7d136c425502aafe4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 11 Dec 2024 23:43:06 +0900 Subject: [PATCH 269/273] feat(duplicated_node_checker): show the node name on the terminal (#9609) Signed-off-by: Takayuki Murooka --- .../src/duplicated_node_checker_core.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp b/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp index 1bc14bf927835..40ced8f886005 100644 --- a/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp +++ b/system/duplicated_node_checker/src/duplicated_node_checker_core.cpp @@ -67,6 +67,8 @@ void DuplicatedNodeChecker::produceDiagnostics(diagnostic_updater::DiagnosticSta } for (auto name : identical_names) { stat.add("Duplicated Node Name", name); + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 5000, "%s node is duplicated.", name.c_str()); } } else { msg = "OK"; From 3cfb03e561abc163439486b332925bd2c42935a4 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Wed, 11 Dec 2024 23:44:45 +0900 Subject: [PATCH 270/273] fix(static_centerline_generator): several bug fixes (#9426) * fix: dependent packages Signed-off-by: Takayuki Murooka * feat: use steer angle, use warn for steer angle failure, calc curvature dicontinuously Signed-off-by: Takayuki Murooka * fix cppcheck Signed-off-by: Takayuki Murooka --------- Signed-off-by: Takayuki Murooka --- .../vehicle_info.hpp | 1 + .../src/vehicle_info.cpp | 11 +++++ .../static_centerline_generator.launch.xml | 2 +- .../package.xml | 2 + .../src/static_centerline_generator_node.cpp | 47 +++++++++++-------- 5 files changed, 42 insertions(+), 21 deletions(-) diff --git a/common/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp b/common/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp index 0e783cd006986..51c63418acc29 100644 --- a/common/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp +++ b/common/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp @@ -71,6 +71,7 @@ struct VehicleInfo double calcMaxCurvature() const; double calcCurvatureFromSteerAngle(const double steer_angle) const; + double calcSteerAngleFromCurvature(const double curvature) const; }; /// Create vehicle info from base parameters diff --git a/common/autoware_vehicle_info_utils/src/vehicle_info.cpp b/common/autoware_vehicle_info_utils/src/vehicle_info.cpp index c0a4c240ba44a..c75a4351fb3f3 100644 --- a/common/autoware_vehicle_info_utils/src/vehicle_info.cpp +++ b/common/autoware_vehicle_info_utils/src/vehicle_info.cpp @@ -129,4 +129,15 @@ double VehicleInfo::calcCurvatureFromSteerAngle(const double steer_angle) const const double curvature = 1.0 / radius; return curvature; } + +double VehicleInfo::calcSteerAngleFromCurvature(const double curvature) const +{ + if (std::abs(curvature) < 1e-6) { + return 0.0; + } + + const double radius = 1.0 / curvature; + const double steer_angle = std::atan2(wheel_base_m, radius); + return steer_angle; +} } // namespace autoware::vehicle_info_utils diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml index 9ccc5a183be45..0590009ab378c 100644 --- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml +++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml @@ -48,7 +48,7 @@ - + diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index a6d97d6fae2f7..6ba1494e714cd 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -20,9 +20,11 @@ autoware_global_parameter_loader autoware_interpolation autoware_lanelet2_extension + autoware_lanelet2_map_visualizer autoware_map_loader autoware_map_msgs autoware_map_projection_loader + autoware_map_tf_generator autoware_mission_planner autoware_motion_utils autoware_osqp_interface diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp index 7f0264d02434e..f172e3e0cb1cd 100644 --- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp +++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp @@ -14,13 +14,14 @@ #include "static_centerline_generator_node.hpp" -#include "autoware/interpolation/spline_interpolation_points_2d.hpp" #include "autoware/map_loader/lanelet2_map_loader_node.hpp" #include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp" #include "autoware/map_projection_loader/map_projection_loader.hpp" #include "autoware/motion_utils/resample/resample.hpp" #include "autoware/motion_utils/trajectory/conversion.hpp" +#include "autoware/motion_utils/trajectory/trajectory.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware/universe_utils/math/unit_conversion.hpp" #include "autoware/universe_utils/ros/parameter.hpp" #include "autoware_lanelet2_extension/utility/message_conversion.hpp" #include "autoware_lanelet2_extension/utility/query.hpp" @@ -59,6 +60,7 @@ #define RESET_TEXT "\x1B[0m" #define RED_TEXT "\x1B[31m" +#define YELLOW_TEXT "\x1b[33m" #define BOLD_TEXT "\x1B[1m" namespace autoware::static_centerline_generator @@ -626,10 +628,8 @@ void StaticCenterlineGeneratorNode::validate() } // calculate curvature - autoware::interpolation::SplineInterpolationPoints2d centerline_spline(centerline); - const auto curvature_vec = centerline_spline.getSplineInterpolatedCurvatures(); - const double curvature_threshold = vehicle_info_.calcCurvatureFromSteerAngle( - vehicle_info_.max_steer_angle_rad - max_steer_angle_margin); + const auto curvature_vec = autoware::motion_utils::calcCurvature(centerline); + const double steer_angle_threshold = vehicle_info_.max_steer_angle_rad - max_steer_angle_margin; // calculate the distance between footprint and right/left bounds MarkerArray marker_array; @@ -676,6 +676,7 @@ void StaticCenterlineGeneratorNode::validate() max_curvature = std::abs(curvature); } } + const double max_steer_angle = vehicle_info_.calcSteerAngleFromCurvature(max_curvature); // publish road boundaries const auto left_bound = convertToGeometryPoints(lanelet_left_bound); @@ -693,30 +694,36 @@ void StaticCenterlineGeneratorNode::validate() std::cerr << "1. Footprints inside Lanelets:" << std::endl; if (dist_thresh_to_road_border < min_dist) { std::cerr << " The generated centerline is inside the lanelet. (threshold:" - << dist_thresh_to_road_border << " < actual:" << min_dist << ")" << std::endl + << dist_thresh_to_road_border << "[m] < actual:" << min_dist << "[m])" << std::endl << " Passed." << std::endl; return true; } std::cerr << RED_TEXT << " The generated centerline is outside the lanelet. (actual:" << min_dist - << " <= threshold:" << dist_thresh_to_road_border << ")" << std::endl + << "[m] <= threshold:" << dist_thresh_to_road_border << "[m])" << std::endl << " Failed." << RESET_TEXT << std::endl; return false; }(); // 2. centerline's curvature - const bool is_curvature_low = [&]() { - std::cerr << "2. Curvature:" << std::endl; - if (max_curvature < curvature_threshold) { - std::cerr << " The generated centerline has no high curvature. (actual:" << max_curvature - << " < threshold:" << curvature_threshold << ")" - << " Passed." << std::endl; - return true; - } - std::cerr << RED_TEXT << " The generated centerline has a too high curvature. (threshold:" - << curvature_threshold << " <= actual:" << max_curvature << ")" - << " Failed." << RESET_TEXT << std::endl; - return false; - }(); + std::cerr << "2. Curvature:" << std::endl; + const bool is_curvature_low = + true; // always tre for now since the curvature is just estimated and not enough precise. + if (max_steer_angle < steer_angle_threshold) { + std::cerr << " The generated centerline has no high steer angle. (estimated:" + << autoware::universe_utils::rad2deg(max_steer_angle) + << "[deg] < threshold:" << autoware::universe_utils::rad2deg(steer_angle_threshold) + << "[deg])" << std::endl + << " Passed." << std::endl; + } else { + std::cerr << YELLOW_TEXT << " The generated centerline has a too high steer angle. (threshold:" + << autoware::universe_utils::rad2deg(steer_angle_threshold) + << "[deg] <= estimated:" << autoware::universe_utils::rad2deg(max_steer_angle) + << "[deg])" << std::endl + << " However, the estimated steer angle is not enough precise, so the result is " + "conditional pass." + << std::endl + << " Conditionally Passed." << RESET_TEXT << std::endl; + } // 3. result std::cerr << std::endl << BOLD_TEXT << "Result:" << RESET_TEXT << std::endl; if (are_footprints_inside_lanelets && is_curvature_low) { From e30350c358531a2c5dc2a132de9ad4f85fa370dc Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 12 Dec 2024 11:30:06 +0900 Subject: [PATCH 271/273] refactor(autoware_multi_object_tracker): merge normal_vehicle_tracker and big_vehicle_tracker (#9613) * refactor: define object_model_ at initialization * refactor: combine normal and big vehicle tracker --- .../CMakeLists.txt | 3 +- .../model/multiple_vehicle_tracker.hpp | 7 +- .../tracker/model/normal_vehicle_tracker.hpp | 78 ---- ...ehicle_tracker.hpp => vehicle_tracker.hpp} | 18 +- .../multi_object_tracker/tracker/tracker.hpp | 3 +- .../lib/tracker/model/big_vehicle_tracker.cpp | 362 ------------------ .../model/multiple_vehicle_tracker.cpp | 8 +- ...ehicle_tracker.cpp => vehicle_tracker.cpp} | 32 +- .../src/processor/processor.cpp | 9 +- 9 files changed, 41 insertions(+), 479 deletions(-) delete mode 100644 perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp rename perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/{big_vehicle_tracker.hpp => vehicle_tracker.hpp} (82%) delete mode 100644 perception/autoware_multi_object_tracker/lib/tracker/model/big_vehicle_tracker.cpp rename perception/autoware_multi_object_tracker/lib/tracker/model/{normal_vehicle_tracker.cpp => vehicle_tracker.cpp} (92%) diff --git a/perception/autoware_multi_object_tracker/CMakeLists.txt b/perception/autoware_multi_object_tracker/CMakeLists.txt index 73edabaa09429..298b6605192a5 100644 --- a/perception/autoware_multi_object_tracker/CMakeLists.txt +++ b/perception/autoware_multi_object_tracker/CMakeLists.txt @@ -36,8 +36,7 @@ set(${PROJECT_NAME}_lib lib/tracker/motion_model/ctrv_motion_model.cpp lib/tracker/motion_model/cv_motion_model.cpp lib/tracker/model/tracker_base.cpp - lib/tracker/model/big_vehicle_tracker.cpp - lib/tracker/model/normal_vehicle_tracker.cpp + lib/tracker/model/vehicle_tracker.cpp lib/tracker/model/multiple_vehicle_tracker.cpp lib/tracker/model/bicycle_tracker.cpp lib/tracker/model/pedestrian_tracker.cpp diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp index 868aa1606d4ff..8b4fa1babf652 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp @@ -20,9 +20,8 @@ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__MULTIPLE_VEHICLE_TRACKER_HPP_ #include "autoware/kalman_filter/kalman_filter.hpp" -#include "autoware/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp" -#include "autoware/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp" #include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" +#include "autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp" #include @@ -32,8 +31,8 @@ namespace autoware::multi_object_tracker class MultipleVehicleTracker : public Tracker { private: - NormalVehicleTracker normal_vehicle_tracker_; - BigVehicleTracker big_vehicle_tracker_; + VehicleTracker normal_vehicle_tracker_; + VehicleTracker big_vehicle_tracker_; public: MultipleVehicleTracker( diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp deleted file mode 100644 index 0bfc065c7cc68..0000000000000 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp +++ /dev/null @@ -1,78 +0,0 @@ -// Copyright 2020 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. -// -// -// Author: v1.0 Yukihiro Saito -// - -#ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_ -#define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_ - -#include "autoware/kalman_filter/kalman_filter.hpp" -#include "autoware/multi_object_tracker/object_model/object_model.hpp" -#include "autoware/multi_object_tracker/tracker/model/tracker_base.hpp" -#include "autoware/multi_object_tracker/tracker/motion_model/bicycle_motion_model.hpp" - -namespace autoware::multi_object_tracker -{ - -class NormalVehicleTracker : public Tracker -{ -private: - autoware_perception_msgs::msg::DetectedObject object_; - rclcpp::Logger logger_; - - object_model::ObjectModel object_model_ = object_model::normal_vehicle; - - double velocity_deviation_threshold_; - - double z_; - - struct BoundingBox - { - double length; - double width; - double height; - }; - BoundingBox bounding_box_; - Eigen::Vector2d tracking_offset_; - - BicycleMotionModel motion_model_; - using IDX = BicycleMotionModel::IDX; - -public: - NormalVehicleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, - const uint & channel_index); - - bool predict(const rclcpp::Time & time) override; - bool measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform) override; - bool measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object); - bool measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object); - bool getTrackedObject( - const rclcpp::Time & time, - autoware_perception_msgs::msg::TrackedObject & object) const override; - -private: - autoware_perception_msgs::msg::DetectedObject getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform); -}; - -} // namespace autoware::multi_object_tracker - -#endif // AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__NORMAL_VEHICLE_TRACKER_HPP_ diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp similarity index 82% rename from perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp rename to perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp index 489f656f750cb..f3708fd1ff905 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp @@ -16,8 +16,8 @@ // Author: v1.0 Yukihiro Saito // -#ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_ -#define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_ +#ifndef AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__VEHICLE_TRACKER_HPP_ +#define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__VEHICLE_TRACKER_HPP_ #include "autoware/kalman_filter/kalman_filter.hpp" #include "autoware/multi_object_tracker/object_model/object_model.hpp" @@ -27,16 +27,15 @@ namespace autoware::multi_object_tracker { -class BigVehicleTracker : public Tracker +class VehicleTracker : public Tracker { private: - autoware_perception_msgs::msg::DetectedObject object_; + object_model::ObjectModel object_model_; rclcpp::Logger logger_; - object_model::ObjectModel object_model_ = object_model::big_vehicle; - double velocity_deviation_threshold_; + autoware_perception_msgs::msg::DetectedObject object_; double z_; struct BoundingBox @@ -52,8 +51,9 @@ class BigVehicleTracker : public Tracker using IDX = BicycleMotionModel::IDX; public: - BigVehicleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, + VehicleTracker( + const object_model::ObjectModel & object_model, const rclcpp::Time & time, + const autoware_perception_msgs::msg::DetectedObject & object, const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, const uint & channel_index); @@ -75,4 +75,4 @@ class BigVehicleTracker : public Tracker } // namespace autoware::multi_object_tracker -#endif // AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__BIG_VEHICLE_TRACKER_HPP_ +#endif // AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__MODEL__VEHICLE_TRACKER_HPP_ diff --git a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/tracker.hpp b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/tracker.hpp index ea1e60d4c7e17..ecf727c36936c 100644 --- a/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/tracker.hpp +++ b/perception/autoware_multi_object_tracker/include/autoware/multi_object_tracker/tracker/tracker.hpp @@ -20,13 +20,12 @@ #define AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__TRACKER_HPP_ #include "model/bicycle_tracker.hpp" -#include "model/big_vehicle_tracker.hpp" #include "model/multiple_vehicle_tracker.hpp" -#include "model/normal_vehicle_tracker.hpp" #include "model/pass_through_tracker.hpp" #include "model/pedestrian_and_bicycle_tracker.hpp" #include "model/pedestrian_tracker.hpp" #include "model/tracker_base.hpp" #include "model/unknown_tracker.hpp" +#include "model/vehicle_tracker.hpp" #endif // AUTOWARE__MULTI_OBJECT_TRACKER__TRACKER__TRACKER_HPP_ diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/big_vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/big_vehicle_tracker.cpp deleted file mode 100644 index 349ffb1eec634..0000000000000 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/big_vehicle_tracker.cpp +++ /dev/null @@ -1,362 +0,0 @@ -// Copyright 2020 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. -// -// -// Author: v1.0 Yukihiro Saito -// -#define EIGEN_MPL2_ONLY - -#include "autoware/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp" - -#include "autoware/multi_object_tracker/utils/utils.hpp" -#include "autoware/object_recognition_utils/object_recognition_utils.hpp" -#include "autoware/universe_utils/geometry/boost_polygon_utils.hpp" -#include "autoware/universe_utils/math/normalization.hpp" -#include "autoware/universe_utils/math/unit_conversion.hpp" -#include "autoware/universe_utils/ros/msg_covariance.hpp" - -#include -#include - -#include -#include -#include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - -namespace autoware::multi_object_tracker -{ -using Label = autoware_perception_msgs::msg::ObjectClassification; - -BigVehicleTracker::BigVehicleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, - const uint & channel_index) -: Tracker(time, object.classification, channel_size), - logger_(rclcpp::get_logger("BigVehicleTracker")), - z_(object.kinematics.pose_with_covariance.pose.position.z), - tracking_offset_(Eigen::Vector2d::Zero()) -{ - object_ = object; - - // initialize existence probability - initializeExistenceProbabilities(channel_index, object.existence_probability); - - // velocity deviation threshold - // if the predicted velocity is close to the observed velocity, - // the observed velocity is used as the measurement. - velocity_deviation_threshold_ = autoware::universe_utils::kmph2mps(10); // [m/s] - - // OBJECT SHAPE MODEL - if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - bounding_box_ = { - object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; - } else { - autoware_perception_msgs::msg::DetectedObject bbox_object; - if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { - RCLCPP_WARN( - logger_, - "BigVehicleTracker::BigVehicleTracker: Failed to convert convex hull to bounding box."); - bounding_box_ = { - object_model_.init_size.length, object_model_.init_size.width, - object_model_.init_size.height}; // default value - } else { - bounding_box_ = { - bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, - bbox_object.shape.dimensions.z}; - } - } - // set maximum and minimum size - bounding_box_.length = std::clamp( - bounding_box_.length, object_model_.size_limit.length_min, object_model_.size_limit.length_max); - bounding_box_.width = std::clamp( - bounding_box_.width, object_model_.size_limit.width_min, object_model_.size_limit.width_max); - bounding_box_.height = std::clamp( - bounding_box_.height, object_model_.size_limit.height_min, object_model_.size_limit.height_max); - - // Set motion model parameters - { - const double q_stddev_acc_long = object_model_.process_noise.acc_long; - const double q_stddev_acc_lat = object_model_.process_noise.acc_lat; - const double q_stddev_yaw_rate_min = object_model_.process_noise.yaw_rate_min; - const double q_stddev_yaw_rate_max = object_model_.process_noise.yaw_rate_max; - const double q_stddev_slip_rate_min = object_model_.bicycle_state.slip_rate_stddev_min; - const double q_stddev_slip_rate_max = object_model_.bicycle_state.slip_rate_stddev_max; - const double q_max_slip_angle = object_model_.bicycle_state.slip_angle_max; - const double lf_ratio = object_model_.bicycle_state.wheel_pos_ratio_front; - const double lf_min = object_model_.bicycle_state.wheel_pos_front_min; - const double lr_ratio = object_model_.bicycle_state.wheel_pos_ratio_rear; - const double lr_min = object_model_.bicycle_state.wheel_pos_rear_min; - motion_model_.setMotionParams( - q_stddev_acc_long, q_stddev_acc_lat, q_stddev_yaw_rate_min, q_stddev_yaw_rate_max, - q_stddev_slip_rate_min, q_stddev_slip_rate_max, q_max_slip_angle, lf_ratio, lf_min, lr_ratio, - lr_min); - } - - // Set motion limits - { - const double max_vel = object_model_.process_limit.vel_long_max; - const double max_slip = object_model_.bicycle_state.slip_angle_max; - motion_model_.setMotionLimits(max_vel, max_slip); // maximum velocity and slip angle - } - - // Set initial state - { - using autoware::universe_utils::xyzrpy_covariance_index::XYZRPY_COV_IDX; - const double x = object.kinematics.pose_with_covariance.pose.position.x; - const double y = object.kinematics.pose_with_covariance.pose.position.y; - const double yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); - - auto pose_cov = object.kinematics.pose_with_covariance.covariance; - if (!object.kinematics.has_position_covariance) { - // initial state covariance - const auto & p0_cov_x = object_model_.initial_covariance.pos_x; - const auto & p0_cov_y = object_model_.initial_covariance.pos_y; - const auto & p0_cov_yaw = object_model_.initial_covariance.yaw; - - const double cos_yaw = std::cos(yaw); - const double sin_yaw = std::sin(yaw); - const double sin_2yaw = std::sin(2.0 * yaw); - pose_cov[XYZRPY_COV_IDX::X_X] = p0_cov_x * cos_yaw * cos_yaw + p0_cov_y * sin_yaw * sin_yaw; - pose_cov[XYZRPY_COV_IDX::X_Y] = 0.5 * (p0_cov_x - p0_cov_y) * sin_2yaw; - pose_cov[XYZRPY_COV_IDX::Y_Y] = p0_cov_x * sin_yaw * sin_yaw + p0_cov_y * cos_yaw * cos_yaw; - pose_cov[XYZRPY_COV_IDX::Y_X] = pose_cov[XYZRPY_COV_IDX::X_Y]; - pose_cov[XYZRPY_COV_IDX::YAW_YAW] = p0_cov_yaw; - } - - double vel = 0.0; - double vel_cov = object_model_.initial_covariance.vel_long; - if (object.kinematics.has_twist) { - vel = object.kinematics.twist_with_covariance.twist.linear.x; - } - if (object.kinematics.has_twist_covariance) { - vel_cov = object.kinematics.twist_with_covariance.covariance[XYZRPY_COV_IDX::X_X]; - } - - const double slip = 0.0; - const double slip_cov = object_model_.bicycle_state.init_slip_angle_cov; - const double & length = bounding_box_.length; - - // initialize motion model - motion_model_.initialize(time, x, y, yaw, pose_cov, vel, vel_cov, slip, slip_cov, length); - } -} - -bool BigVehicleTracker::predict(const rclcpp::Time & time) -{ - return motion_model_.predictState(time); -} - -autoware_perception_msgs::msg::DetectedObject BigVehicleTracker::getUpdatingObject( - const autoware_perception_msgs::msg::DetectedObject & object, - const geometry_msgs::msg::Transform & self_transform) -{ - autoware_perception_msgs::msg::DetectedObject updating_object = object; - - // OBJECT SHAPE MODEL - // convert to bounding box if input is convex shape - autoware_perception_msgs::msg::DetectedObject bbox_object = object; - if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { - RCLCPP_WARN( - logger_, - "BigVehicleTracker::getUpdatingObject: Failed to convert convex hull to bounding box."); - bbox_object = object; - } - } - - // current (predicted) state - const double tracked_x = motion_model_.getStateElement(IDX::X); - const double tracked_y = motion_model_.getStateElement(IDX::Y); - const double tracked_yaw = motion_model_.getStateElement(IDX::YAW); - - // get offset measurement - const int nearest_corner_index = utils::getNearestCornerOrSurface( - tracked_x, tracked_y, tracked_yaw, bounding_box_.width, bounding_box_.length, self_transform); - utils::calcAnchorPointOffset( - bounding_box_.width, bounding_box_.length, nearest_corner_index, bbox_object, tracked_yaw, - updating_object, tracking_offset_); - - return updating_object; -} - -bool BigVehicleTracker::measureWithPose( - const autoware_perception_msgs::msg::DetectedObject & object) -{ - // current (predicted) state - const double tracked_vel = motion_model_.getStateElement(IDX::VEL); - - // velocity capability is checked only when the object has velocity measurement - // and the predicted velocity is close to the observed velocity - bool is_velocity_available = false; - if (object.kinematics.has_twist) { - const double & observed_vel = object.kinematics.twist_with_covariance.twist.linear.x; - if (std::fabs(tracked_vel - observed_vel) < velocity_deviation_threshold_) { - // Velocity deviation is small - is_velocity_available = true; - } - } - - // update - bool is_updated = false; - { - const double x = object.kinematics.pose_with_covariance.pose.position.x; - const double y = object.kinematics.pose_with_covariance.pose.position.y; - const double yaw = tf2::getYaw(object.kinematics.pose_with_covariance.pose.orientation); - const double vel = object.kinematics.twist_with_covariance.twist.linear.x; - - if (is_velocity_available) { - is_updated = motion_model_.updateStatePoseHeadVel( - x, y, yaw, object.kinematics.pose_with_covariance.covariance, vel, - object.kinematics.twist_with_covariance.covariance); - } else { - is_updated = motion_model_.updateStatePoseHead( - x, y, yaw, object.kinematics.pose_with_covariance.covariance); - } - motion_model_.limitStates(); - } - - // position z - constexpr double gain = 0.1; - z_ = (1.0 - gain) * z_ + gain * object.kinematics.pose_with_covariance.pose.position.z; - - return is_updated; -} - -bool BigVehicleTracker::measureWithShape( - const autoware_perception_msgs::msg::DetectedObject & object) -{ - if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - // do not update shape if the input is not a bounding box - return false; - } - - // check object size abnormality - constexpr double size_max = 35.0; // [m] - constexpr double size_min = 1.0; // [m] - bool is_size_valid = - (object.shape.dimensions.x <= size_max && object.shape.dimensions.y <= size_max && - object.shape.dimensions.x >= size_min && object.shape.dimensions.y >= size_min); - if (!is_size_valid) { - return false; - } - - // update object size - constexpr double gain = 0.5; - constexpr double gain_inv = 1.0 - gain; - bounding_box_.length = gain_inv * bounding_box_.length + gain * object.shape.dimensions.x; - bounding_box_.width = gain_inv * bounding_box_.width + gain * object.shape.dimensions.y; - bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z; - - // set maximum and minimum size - bounding_box_.length = std::clamp( - bounding_box_.length, object_model_.size_limit.length_min, object_model_.size_limit.length_max); - bounding_box_.width = std::clamp( - bounding_box_.width, object_model_.size_limit.width_min, object_model_.size_limit.width_max); - bounding_box_.height = std::clamp( - bounding_box_.height, object_model_.size_limit.height_min, object_model_.size_limit.height_max); - - // update motion model - motion_model_.updateExtendedState(bounding_box_.length); - - // update offset into object position - { - // rotate back the offset vector from object coordinate to global coordinate - const double yaw = motion_model_.getStateElement(IDX::YAW); - const double offset_x_global = - tracking_offset_.x() * std::cos(yaw) - tracking_offset_.y() * std::sin(yaw); - const double offset_y_global = - tracking_offset_.x() * std::sin(yaw) + tracking_offset_.y() * std::cos(yaw); - motion_model_.adjustPosition(-gain * offset_x_global, -gain * offset_y_global); - // update offset (object coordinate) - tracking_offset_.x() = gain_inv * tracking_offset_.x(); - tracking_offset_.y() = gain_inv * tracking_offset_.y(); - } - - return true; -} - -bool BigVehicleTracker::measure( - const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, - const geometry_msgs::msg::Transform & self_transform) -{ - // keep the latest input object - object_ = object; - - // update classification - const auto & current_classification = getClassification(); - if ( - autoware::object_recognition_utils::getHighestProbLabel(object.classification) == - Label::UNKNOWN) { - setClassification(current_classification); - } - - // check time gap - const double dt = motion_model_.getDeltaTime(time); - if (0.01 /*10msec*/ < dt) { - RCLCPP_WARN( - logger_, - "BigVehicleTracker::measure There is a large gap between predicted time and measurement " - "time. (%f)", - dt); - } - - // update object - const autoware_perception_msgs::msg::DetectedObject updating_object = - getUpdatingObject(object, self_transform); - measureWithPose(updating_object); - measureWithShape(updating_object); - - return true; -} - -bool BigVehicleTracker::getTrackedObject( - const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const -{ - object = autoware::object_recognition_utils::toTrackedObject(object_); - object.object_id = getUUID(); - object.classification = getClassification(); - - auto & pose_with_cov = object.kinematics.pose_with_covariance; - auto & twist_with_cov = object.kinematics.twist_with_covariance; - - // predict from motion model - if (!motion_model_.getPredictedState( - time, pose_with_cov.pose, pose_with_cov.covariance, twist_with_cov.twist, - twist_with_cov.covariance)) { - RCLCPP_WARN(logger_, "BigVehicleTracker::getTrackedObject: Failed to get predicted state."); - return false; - } - - // position - pose_with_cov.pose.position.z = z_; - - // set shape - object.shape.dimensions.x = bounding_box_.length; - object.shape.dimensions.y = bounding_box_.width; - object.shape.dimensions.z = bounding_box_.height; - const auto origin_yaw = tf2::getYaw(object_.kinematics.pose_with_covariance.pose.orientation); - const auto ekf_pose_yaw = tf2::getYaw(pose_with_cov.pose.orientation); - object.shape.footprint = - autoware::universe_utils::rotatePolygon(object.shape.footprint, origin_yaw - ekf_pose_yaw); - - return true; -} - -} // namespace autoware::multi_object_tracker diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp index 4751e3d1c894f..ff06544bd509c 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/multiple_vehicle_tracker.cpp @@ -18,6 +18,8 @@ #include "autoware/multi_object_tracker/tracker/model/multiple_vehicle_tracker.hpp" +#include "autoware/multi_object_tracker/object_model/object_model.hpp" + namespace autoware::multi_object_tracker { @@ -28,8 +30,10 @@ MultipleVehicleTracker::MultipleVehicleTracker( const geometry_msgs::msg::Transform & self_transform, const size_t channel_size, const uint & channel_index) : Tracker(time, object.classification, channel_size), - normal_vehicle_tracker_(time, object, self_transform, channel_size, channel_index), - big_vehicle_tracker_(time, object, self_transform, channel_size, channel_index) + normal_vehicle_tracker_( + object_model::normal_vehicle, time, object, self_transform, channel_size, channel_index), + big_vehicle_tracker_( + object_model::big_vehicle, time, object, self_transform, channel_size, channel_index) { // initialize existence probability initializeExistenceProbabilities(channel_index, object.existence_probability); diff --git a/perception/autoware_multi_object_tracker/lib/tracker/model/normal_vehicle_tracker.cpp b/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp similarity index 92% rename from perception/autoware_multi_object_tracker/lib/tracker/model/normal_vehicle_tracker.cpp rename to perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp index b4be5e42b0397..2d1f48a3ad5ee 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/model/normal_vehicle_tracker.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/model/vehicle_tracker.cpp @@ -17,7 +17,7 @@ // #define EIGEN_MPL2_ONLY -#include "autoware/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp" +#include "autoware/multi_object_tracker/tracker/model/vehicle_tracker.hpp" #include "autoware/multi_object_tracker/utils/utils.hpp" #include "autoware/object_recognition_utils/object_recognition_utils.hpp" @@ -45,12 +45,14 @@ namespace autoware::multi_object_tracker using Label = autoware_perception_msgs::msg::ObjectClassification; -NormalVehicleTracker::NormalVehicleTracker( - const rclcpp::Time & time, const autoware_perception_msgs::msg::DetectedObject & object, +VehicleTracker::VehicleTracker( + const object_model::ObjectModel & object_model, const rclcpp::Time & time, + const autoware_perception_msgs::msg::DetectedObject & object, const geometry_msgs::msg::Transform & /*self_transform*/, const size_t channel_size, const uint & channel_index) : Tracker(time, object.classification, channel_size), - logger_(rclcpp::get_logger("NormalVehicleTracker")), + object_model_(object_model), + logger_(rclcpp::get_logger("VehicleTracker")), z_(object.kinematics.pose_with_covariance.pose.position.z), tracking_offset_(Eigen::Vector2d::Zero()) { @@ -73,7 +75,7 @@ NormalVehicleTracker::NormalVehicleTracker( if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { RCLCPP_WARN( logger_, - "NormalVehicleTracker::NormalVehicleTracker: Failed to convert convex hull to bounding " + "VehicleTracker::VehicleTracker: Failed to convert convex hull to bounding " "box."); bounding_box_ = { object_model_.init_size.length, object_model_.init_size.width, @@ -160,12 +162,12 @@ NormalVehicleTracker::NormalVehicleTracker( } } -bool NormalVehicleTracker::predict(const rclcpp::Time & time) +bool VehicleTracker::predict(const rclcpp::Time & time) { return motion_model_.predictState(time); } -autoware_perception_msgs::msg::DetectedObject NormalVehicleTracker::getUpdatingObject( +autoware_perception_msgs::msg::DetectedObject VehicleTracker::getUpdatingObject( const autoware_perception_msgs::msg::DetectedObject & object, const geometry_msgs::msg::Transform & self_transform) { @@ -178,7 +180,7 @@ autoware_perception_msgs::msg::DetectedObject NormalVehicleTracker::getUpdatingO if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) { RCLCPP_WARN( logger_, - "NormalVehicleTracker::getUpdatingObject: Failed to convert convex hull to bounding box."); + "VehicleTracker::getUpdatingObject: Failed to convert convex hull to bounding box."); bbox_object = object; } } @@ -198,8 +200,7 @@ autoware_perception_msgs::msg::DetectedObject NormalVehicleTracker::getUpdatingO return updating_object; } -bool NormalVehicleTracker::measureWithPose( - const autoware_perception_msgs::msg::DetectedObject & object) +bool VehicleTracker::measureWithPose(const autoware_perception_msgs::msg::DetectedObject & object) { // current (predicted) state const double tracked_vel = motion_model_.getStateElement(IDX::VEL); @@ -241,8 +242,7 @@ bool NormalVehicleTracker::measureWithPose( return is_updated; } -bool NormalVehicleTracker::measureWithShape( - const autoware_perception_msgs::msg::DetectedObject & object) +bool VehicleTracker::measureWithShape(const autoware_perception_msgs::msg::DetectedObject & object) { if (object.shape.type != autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { // do not update shape if the input is not a bounding box @@ -294,7 +294,7 @@ bool NormalVehicleTracker::measureWithShape( return true; } -bool NormalVehicleTracker::measure( +bool VehicleTracker::measure( const autoware_perception_msgs::msg::DetectedObject & object, const rclcpp::Time & time, const geometry_msgs::msg::Transform & self_transform) { @@ -314,7 +314,7 @@ bool NormalVehicleTracker::measure( if (0.01 /*10msec*/ < dt) { RCLCPP_WARN( logger_, - "NormalVehicleTracker::measure There is a large gap between predicted time and measurement " + "VehicleTracker::measure There is a large gap between predicted time and measurement " "time. (%f)", dt); } @@ -328,7 +328,7 @@ bool NormalVehicleTracker::measure( return true; } -bool NormalVehicleTracker::getTrackedObject( +bool VehicleTracker::getTrackedObject( const rclcpp::Time & time, autoware_perception_msgs::msg::TrackedObject & object) const { object = autoware::object_recognition_utils::toTrackedObject(object_); @@ -342,7 +342,7 @@ bool NormalVehicleTracker::getTrackedObject( if (!motion_model_.getPredictedState( time, pose_with_cov.pose, pose_with_cov.covariance, twist_with_cov.twist, twist_with_cov.covariance)) { - RCLCPP_WARN(logger_, "NormalVehicleTracker::getTrackedObject: Failed to get predicted state."); + RCLCPP_WARN(logger_, "VehicleTracker::getTrackedObject: Failed to get predicted state."); return false; } diff --git a/perception/autoware_multi_object_tracker/src/processor/processor.cpp b/perception/autoware_multi_object_tracker/src/processor/processor.cpp index f4202c1f6e413..ebc11ea63e199 100644 --- a/perception/autoware_multi_object_tracker/src/processor/processor.cpp +++ b/perception/autoware_multi_object_tracker/src/processor/processor.cpp @@ -14,6 +14,7 @@ #include "processor.hpp" +#include "autoware/multi_object_tracker/object_model/object_model.hpp" #include "autoware/multi_object_tracker/tracker/tracker.hpp" #include "autoware/object_recognition_utils/object_recognition_utils.hpp" @@ -102,14 +103,14 @@ std::shared_ptr TrackerProcessor::createNewTracker( return std::make_shared( time, object, self_transform, channel_size_, channel_index); if (tracker == "big_vehicle_tracker") - return std::make_shared( - time, object, self_transform, channel_size_, channel_index); + return std::make_shared( + object_model::big_vehicle, time, object, self_transform, channel_size_, channel_index); if (tracker == "multi_vehicle_tracker") return std::make_shared( time, object, self_transform, channel_size_, channel_index); if (tracker == "normal_vehicle_tracker") - return std::make_shared( - time, object, self_transform, channel_size_, channel_index); + return std::make_shared( + object_model::normal_vehicle, time, object, self_transform, channel_size_, channel_index); if (tracker == "pass_through_tracker") return std::make_shared( time, object, self_transform, channel_size_, channel_index); From d741026d8824c8240d2945eeb942e5dd9e6dc363 Mon Sep 17 00:00:00 2001 From: Fumiya Watanabe Date: Thu, 12 Dec 2024 12:30:04 +0900 Subject: [PATCH 272/273] chore(package.xml): bump version to 0.40.0 (#9618) Signed-off-by: Fumiya Watanabe --- common/autoware_adapi_specs/CHANGELOG.rst | 30 ++ common/autoware_adapi_specs/package.xml | 2 +- common/autoware_auto_common/CHANGELOG.rst | 26 + common/autoware_auto_common/package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 28 + .../package.xml | 2 +- common/autoware_fake_test_node/CHANGELOG.rst | 15 + common/autoware_fake_test_node/package.xml | 2 +- .../CHANGELOG.rst | 14 + .../package.xml | 2 +- common/autoware_glog_component/CHANGELOG.rst | 15 + common/autoware_glog_component/package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- common/autoware_grid_map_utils/CHANGELOG.rst | 26 + common/autoware_grid_map_utils/package.xml | 2 +- common/autoware_interpolation/CHANGELOG.rst | 26 + common/autoware_interpolation/package.xml | 2 +- common/autoware_kalman_filter/CHANGELOG.rst | 26 + common/autoware_kalman_filter/package.xml | 2 +- common/autoware_motion_utils/CHANGELOG.rst | 69 +++ common/autoware_motion_utils/package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- common/autoware_osqp_interface/CHANGELOG.rst | 27 + common/autoware_osqp_interface/package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- common/autoware_point_types/CHANGELOG.rst | 24 + common/autoware_point_types/package.xml | 2 +- common/autoware_polar_grid/CHANGELOG.rst | 24 + common/autoware_polar_grid/package.xml | 2 +- common/autoware_pyplot/CHANGELOG.rst | 39 ++ common/autoware_pyplot/package.xml | 3 +- common/autoware_qp_interface/CHANGELOG.rst | 29 + common/autoware_qp_interface/package.xml | 2 +- .../autoware_signal_processing/CHANGELOG.rst | 26 + common/autoware_signal_processing/package.xml | 2 +- common/autoware_test_utils/CHANGELOG.rst | 52 ++ common/autoware_test_utils/package.xml | 2 +- common/autoware_testing/CHANGELOG.rst | 24 + common/autoware_testing/package.xml | 2 +- common/autoware_time_utils/CHANGELOG.rst | 32 ++ common/autoware_time_utils/package.xml | 2 +- .../CHANGELOG.rst | 17 + .../package.xml | 2 +- .../CHANGELOG.rst | 16 + .../autoware_traffic_light_utils/package.xml | 2 +- common/autoware_trajectory/CHANGELOG.rst | 43 ++ common/autoware_trajectory/package.xml | 2 +- common/autoware_universe_utils/CHANGELOG.rst | 42 ++ common/autoware_universe_utils/package.xml | 2 +- .../autoware_vehicle_info_utils/CHANGELOG.rst | 31 ++ .../autoware_vehicle_info_utils/package.xml | 2 +- common/tier4_api_utils/CHANGELOG.rst | 24 + common/tier4_api_utils/package.xml | 2 +- .../CHANGELOG.rst | 83 +++ .../package.xml | 2 +- .../autoware_collision_detector/CHANGELOG.rst | 34 ++ .../autoware_collision_detector/package.xml | 2 +- .../autoware_control_validator/CHANGELOG.rst | 30 ++ .../autoware_control_validator/package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- control/autoware_joy_controller/CHANGELOG.rst | 24 + control/autoware_joy_controller/package.xml | 2 +- .../CHANGELOG.rst | 44 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 50 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 28 + .../package.xml | 2 +- .../CHANGELOG.rst | 39 ++ .../package.xml | 2 +- control/autoware_pure_pursuit/CHANGELOG.rst | 29 + control/autoware_pure_pursuit/package.xml | 2 +- control/autoware_shift_decider/CHANGELOG.rst | 24 + control/autoware_shift_decider/package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../CHANGELOG.rst | 34 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 45 ++ .../package.xml | 2 +- .../autoware_vehicle_cmd_gate/CHANGELOG.rst | 31 ++ control/autoware_vehicle_cmd_gate/package.xml | 2 +- .../CHANGELOG.rst | 29 + .../control_performance_analysis/package.xml | 2 +- control/predicted_path_checker/CHANGELOG.rst | 28 + control/predicted_path_checker/package.xml | 2 +- .../autoware_control_evaluator/CHANGELOG.rst | 68 +++ .../autoware_control_evaluator/package.xml | 2 +- .../autoware_planning_evaluator/CHANGELOG.rst | 71 +++ .../autoware_planning_evaluator/package.xml | 2 +- evaluator/kinematic_evaluator/CHANGELOG.rst | 37 ++ evaluator/kinematic_evaluator/package.xml | 2 +- .../localization_evaluator/CHANGELOG.rst | 38 ++ evaluator/localization_evaluator/package.xml | 2 +- .../perception_online_evaluator/CHANGELOG.rst | 38 ++ .../perception_online_evaluator/package.xml | 2 +- .../CHANGELOG.rst | 498 ++++++++++++++++++ .../scenario_simulator_v2_adapter/package.xml | 2 +- .../tier4_autoware_api_launch/CHANGELOG.rst | 24 + launch/tier4_autoware_api_launch/package.xml | 2 +- launch/tier4_control_launch/CHANGELOG.rst | 71 +++ launch/tier4_control_launch/package.xml | 2 +- .../tier4_localization_launch/CHANGELOG.rst | 24 + launch/tier4_localization_launch/package.xml | 2 +- launch/tier4_map_launch/CHANGELOG.rst | 44 ++ launch/tier4_map_launch/package.xml | 2 +- launch/tier4_perception_launch/CHANGELOG.rst | 24 + launch/tier4_perception_launch/package.xml | 2 +- launch/tier4_planning_launch/CHANGELOG.rst | 36 ++ launch/tier4_planning_launch/package.xml | 2 +- launch/tier4_sensing_launch/CHANGELOG.rst | 24 + launch/tier4_sensing_launch/package.xml | 2 +- launch/tier4_simulator_launch/CHANGELOG.rst | 54 ++ launch/tier4_simulator_launch/package.xml | 2 +- launch/tier4_system_launch/CHANGELOG.rst | 24 + launch/tier4_system_launch/package.xml | 2 +- launch/tier4_vehicle_launch/CHANGELOG.rst | 24 + launch/tier4_vehicle_launch/package.xml | 2 +- .../autoware_ekf_localizer/CHANGELOG.rst | 31 ++ .../autoware_ekf_localizer/package.xml | 2 +- .../autoware_geo_pose_projector/CHANGELOG.rst | 29 + .../autoware_geo_pose_projector/package.xml | 2 +- .../autoware_gyro_odometer/CHANGELOG.rst | 24 + .../autoware_gyro_odometer/package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../autoware_landmark_manager/CHANGELOG.rst | 26 + .../autoware_landmark_manager/package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- .../autoware_localization_util/CHANGELOG.rst | 26 + .../autoware_localization_util/package.xml | 2 +- .../autoware_ndt_scan_matcher/CHANGELOG.rst | 65 +++ .../autoware_ndt_scan_matcher/package.xml | 2 +- .../autoware_pose2twist/CHANGELOG.rst | 24 + localization/autoware_pose2twist/package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../autoware_pose_initializer/CHANGELOG.rst | 28 + .../autoware_pose_initializer/package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../autoware_stop_filter/CHANGELOG.rst | 24 + localization/autoware_stop_filter/package.xml | 2 +- .../autoware_twist2accel/CHANGELOG.rst | 24 + localization/autoware_twist2accel/package.xml | 2 +- .../yabloc/yabloc_common/CHANGELOG.rst | 26 + localization/yabloc/yabloc_common/package.xml | 2 +- .../yabloc_image_processing/CHANGELOG.rst | 26 + .../yabloc_image_processing/package.xml | 2 +- .../yabloc/yabloc_monitor/CHANGELOG.rst | 24 + .../yabloc/yabloc_monitor/package.xml | 2 +- .../yabloc_particle_filter/CHANGELOG.rst | 26 + .../yabloc/yabloc_particle_filter/package.xml | 2 +- .../yabloc_pose_initializer/CHANGELOG.rst | 27 + .../yabloc_pose_initializer/package.xml | 2 +- .../CHANGELOG.rst | 465 ++++++++++++++++ .../package.xml | 2 +- map/autoware_map_height_fitter/CHANGELOG.rst | 26 + map/autoware_map_height_fitter/package.xml | 2 +- map/autoware_map_loader/CHANGELOG.rst | 39 ++ map/autoware_map_loader/package.xml | 2 +- .../CHANGELOG.rst | 49 ++ .../package.xml | 2 +- map/autoware_map_tf_generator/CHANGELOG.rst | 26 + map/autoware_map_tf_generator/package.xml | 2 +- perception/autoware_bytetrack/CHANGELOG.rst | 34 ++ perception/autoware_bytetrack/package.xml | 2 +- .../autoware_cluster_merger/CHANGELOG.rst | 26 + .../autoware_cluster_merger/package.xml | 2 +- .../CHANGELOG.rst | 31 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 31 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 49 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 24 + .../autoware_detection_by_tracker/package.xml | 2 +- .../CHANGELOG.rst | 26 + .../autoware_elevation_map_loader/package.xml | 2 +- .../autoware_euclidean_cluster/CHANGELOG.rst | 29 + .../autoware_euclidean_cluster/package.xml | 2 +- .../CHANGELOG.rst | 117 ++++ .../autoware_ground_segmentation/package.xml | 2 +- .../CHANGELOG.rst | 72 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 29 + .../package.xml | 2 +- .../autoware_lidar_centerpoint/CHANGELOG.rst | 46 ++ .../autoware_lidar_centerpoint/package.xml | 2 +- .../autoware_lidar_transfusion/CHANGELOG.rst | 33 ++ .../autoware_lidar_transfusion/package.xml | 2 +- .../CHANGELOG.rst | 45 ++ .../autoware_map_based_prediction/package.xml | 2 +- .../CHANGELOG.rst | 51 ++ .../autoware_multi_object_tracker/package.xml | 2 +- .../autoware_object_merger/CHANGELOG.rst | 26 + perception/autoware_object_merger/package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- .../CHANGELOG.rst | 29 + .../package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../autoware_radar_object_tracker/package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../autoware_shape_estimation/CHANGELOG.rst | 29 + .../autoware_shape_estimation/package.xml | 2 +- .../CHANGELOG.rst | 24 + .../autoware_simple_object_merger/package.xml | 2 +- .../CHANGELOG.rst | 29 + .../autoware_tensorrt_classifier/package.xml | 2 +- .../autoware_tensorrt_common/CHANGELOG.rst | 27 + .../autoware_tensorrt_common/package.xml | 2 +- .../autoware_tensorrt_yolox/CHANGELOG.rst | 30 ++ .../autoware_tensorrt_yolox/package.xml | 2 +- .../CHANGELOG.rst | 29 + .../package.xml | 2 +- .../CHANGELOG.rst | 31 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 33 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 31 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 31 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 35 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 32 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 34 ++ .../package.xml | 2 +- perception/perception_utils/CHANGELOG.rst | 27 + perception/perception_utils/package.xml | 2 +- .../autoware_costmap_generator/CHANGELOG.rst | 51 ++ .../autoware_costmap_generator/package.xml | 2 +- .../CHANGELOG.rst | 31 ++ .../package.xml | 2 +- .../autoware_freespace_planner/CHANGELOG.rst | 41 ++ .../autoware_freespace_planner/package.xml | 2 +- .../CHANGELOG.rst | 48 ++ .../package.xml | 2 +- .../autoware_mission_planner/CHANGELOG.rst | 43 ++ planning/autoware_mission_planner/package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 64 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 28 + .../package.xml | 2 +- .../autoware_path_optimizer/CHANGELOG.rst | 31 ++ planning/autoware_path_optimizer/package.xml | 2 +- planning/autoware_path_smoother/CHANGELOG.rst | 28 + planning/autoware_path_smoother/package.xml | 2 +- .../CHANGELOG.rst | 31 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../autoware_planning_validator/CHANGELOG.rst | 26 + .../autoware_planning_validator/package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- planning/autoware_route_handler/CHANGELOG.rst | 28 + planning/autoware_route_handler/package.xml | 2 +- planning/autoware_rtc_interface/CHANGELOG.rst | 38 ++ planning/autoware_rtc_interface/package.xml | 2 +- .../autoware_scenario_selector/CHANGELOG.rst | 31 ++ .../autoware_scenario_selector/package.xml | 2 +- .../CHANGELOG.rst | 55 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 37 ++ .../package.xml | 2 +- .../autoware_velocity_smoother/CHANGELOG.rst | 34 ++ .../autoware_velocity_smoother/package.xml | 2 +- .../CHANGELOG.rst | 37 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 37 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 37 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 82 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 286 ++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 44 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 137 +++++ .../package.xml | 2 +- .../CHANGELOG.rst | 43 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 41 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 64 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 76 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 32 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 31 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 38 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 40 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../CHANGELOG.rst | 38 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../CHANGELOG.rst | 51 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 60 +++ .../package.xml | 2 +- .../CHANGELOG.rst | 50 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../CHANGELOG.rst | 50 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 46 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 27 + .../package.xml | 2 +- .../CHANGELOG.rst | 29 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 28 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 50 ++ .../package.xml | 2 +- .../autoware_bezier_sampler/CHANGELOG.rst | 26 + .../autoware_bezier_sampler/package.xml | 2 +- .../autoware_frenet_planner/CHANGELOG.rst | 26 + .../autoware_frenet_planner/package.xml | 2 +- .../autoware_path_sampler/CHANGELOG.rst | 27 + .../autoware_path_sampler/package.xml | 2 +- .../autoware_sampler_common/CHANGELOG.rst | 27 + .../autoware_sampler_common/package.xml | 2 +- sensing/autoware_cuda_utils/CHANGELOG.rst | 34 +- sensing/autoware_cuda_utils/package.xml | 2 +- sensing/autoware_gnss_poser/CHANGELOG.rst | 28 + sensing/autoware_gnss_poser/package.xml | 2 +- .../autoware_image_diagnostics/CHANGELOG.rst | 26 + .../autoware_image_diagnostics/package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- sensing/autoware_imu_corrector/CHANGELOG.rst | 26 + sensing/autoware_imu_corrector/package.xml | 2 +- sensing/autoware_pcl_extensions/CHANGELOG.rst | 24 + sensing/autoware_pcl_extensions/package.xml | 2 +- .../CHANGELOG.rst | 44 ++ .../package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- .../CHANGELOG.rst | 24 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 18 + .../package.xml | 2 +- .../autoware_livox_tag_filter/CHANGELOG.rst | 24 + .../autoware_livox_tag_filter/package.xml | 2 +- .../autoware_carla_interface/CHANGELOG.rst | 28 + .../autoware_carla_interface/package.xml | 2 +- simulator/autoware_carla_interface/setup.py | 2 +- .../dummy_perception_publisher/CHANGELOG.rst | 27 + .../dummy_perception_publisher/package.xml | 2 +- simulator/fault_injection/CHANGELOG.rst | 26 + simulator/fault_injection/package.xml | 2 +- .../CHANGELOG.rst | 27 + .../learning_based_vehicle_model/package.xml | 2 +- .../simple_planning_simulator/CHANGELOG.rst | 33 ++ .../simple_planning_simulator/package.xml | 2 +- .../CHANGELOG.rst | 28 + .../package.xml | 2 +- .../vehicle_door_simulator/CHANGELOG.rst | 24 + simulator/vehicle_door_simulator/package.xml | 2 +- .../autoware_component_monitor/CHANGELOG.rst | 26 + system/autoware_component_monitor/package.xml | 2 +- system/autoware_default_adapi/CHANGELOG.rst | 48 ++ system/autoware_default_adapi/package.xml | 2 +- .../CHANGELOG.rst | 56 ++ .../package.xml | 2 +- system/bluetooth_monitor/CHANGELOG.rst | 26 + system/bluetooth_monitor/package.xml | 2 +- system/component_state_monitor/CHANGELOG.rst | 26 + system/component_state_monitor/package.xml | 2 +- .../ad_api_adaptors/CHANGELOG.rst | 36 ++ .../ad_api_adaptors/package.xml | 2 +- .../ad_api_visualizers/CHANGELOG.rst | 24 + .../ad_api_visualizers/package.xml | 2 +- .../ad_api_visualizers/setup.py | 2 +- .../automatic_pose_initializer/CHANGELOG.rst | 36 ++ .../automatic_pose_initializer/package.xml | 2 +- .../diagnostic_graph_aggregator/CHANGELOG.rst | 28 + .../diagnostic_graph_aggregator/package.xml | 2 +- system/diagnostic_graph_utils/CHANGELOG.rst | 39 ++ system/diagnostic_graph_utils/package.xml | 2 +- system/dummy_diag_publisher/CHANGELOG.rst | 36 ++ system/dummy_diag_publisher/package.xml | 2 +- system/dummy_infrastructure/CHANGELOG.rst | 24 + system/dummy_infrastructure/package.xml | 2 +- system/duplicated_node_checker/CHANGELOG.rst | 27 + system/duplicated_node_checker/package.xml | 2 +- system/hazard_status_converter/CHANGELOG.rst | 35 ++ system/hazard_status_converter/package.xml | 2 +- .../CHANGELOG.rst | 30 ++ .../mrm_comfortable_stop_operator/package.xml | 2 +- .../mrm_emergency_stop_operator/CHANGELOG.rst | 26 + .../mrm_emergency_stop_operator/package.xml | 2 +- system/mrm_handler/CHANGELOG.rst | 31 ++ system/mrm_handler/package.xml | 2 +- .../system_diagnostic_monitor/CHANGELOG.rst | 24 + system/system_diagnostic_monitor/package.xml | 2 +- system/system_monitor/CHANGELOG.rst | 37 ++ system/system_monitor/package.xml | 2 +- system/topic_state_monitor/CHANGELOG.rst | 24 + system/topic_state_monitor/package.xml | 2 +- system/velodyne_monitor/CHANGELOG.rst | 24 + system/velodyne_monitor/package.xml | 2 +- tools/reaction_analyzer/CHANGELOG.rst | 26 + tools/reaction_analyzer/package.xml | 2 +- .../CHANGELOG.rst | 28 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 26 + .../package.xml | 2 +- .../CHANGELOG.rst | 8 + .../package.xml | 2 +- .../CHANGELOG.rst | 8 + .../autoware_overlay_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 8 + .../package.xml | 2 +- .../CHANGELOG.rst | 8 + .../bag_time_manager_rviz_plugin/package.xml | 2 +- .../tier4_adapi_rviz_plugin/CHANGELOG.rst | 8 + .../tier4_adapi_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 8 + .../tier4_camera_view_rviz_plugin/package.xml | 2 +- .../tier4_datetime_rviz_plugin/CHANGELOG.rst | 8 + .../tier4_datetime_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 8 + .../package.xml | 2 +- .../tier4_planning_rviz_plugin/CHANGELOG.rst | 8 + .../tier4_planning_rviz_plugin/package.xml | 2 +- .../tier4_state_rviz_plugin/CHANGELOG.rst | 8 + .../tier4_state_rviz_plugin/package.xml | 2 +- .../tier4_system_rviz_plugin/CHANGELOG.rst | 8 + .../tier4_system_rviz_plugin/package.xml | 2 +- .../CHANGELOG.rst | 8 + .../package.xml | 2 +- .../tier4_vehicle_rviz_plugin/CHANGELOG.rst | 8 + .../tier4_vehicle_rviz_plugin/package.xml | 2 +- 494 files changed, 9294 insertions(+), 251 deletions(-) create mode 100644 common/autoware_pyplot/CHANGELOG.rst create mode 100644 evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst create mode 100644 map/autoware_lanelet2_map_visualizer/CHANGELOG.rst diff --git a/common/autoware_adapi_specs/CHANGELOG.rst b/common/autoware_adapi_specs/CHANGELOG.rst index 79e62f7738922..7693074353d9f 100644 --- a/common/autoware_adapi_specs/CHANGELOG.rst +++ b/common/autoware_adapi_specs/CHANGELOG.rst @@ -2,6 +2,36 @@ Changelog for package autoware_adapi_specs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix: fix package names in changelog files (`#9500 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/common/autoware_adapi_specs/package.xml b/common/autoware_adapi_specs/package.xml index 754edf9ddfbe7..5424d5bad52d5 100644 --- a/common/autoware_adapi_specs/package.xml +++ b/common/autoware_adapi_specs/package.xml @@ -2,7 +2,7 @@ autoware_adapi_specs - 0.39.0 + 0.40.0 The autoware_adapi_specs package Takagi, Isamu Ryohsuke Mitsudome diff --git a/common/autoware_auto_common/CHANGELOG.rst b/common/autoware_auto_common/CHANGELOG.rst index 93b2dba7939a2..63f0fe2ac83e3 100644 --- a/common/autoware_auto_common/CHANGELOG.rst +++ b/common/autoware_auto_common/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_auto_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/common/autoware_auto_common/package.xml b/common/autoware_auto_common/package.xml index 9d12bda8c75c3..ccdcd4bab8608 100644 --- a/common/autoware_auto_common/package.xml +++ b/common/autoware_auto_common/package.xml @@ -2,7 +2,7 @@ autoware_auto_common - 0.39.0 + 0.40.0 Miscellaneous helper functions Apex.AI, Inc. Tomoya Kimura diff --git a/common/autoware_component_interface_specs/CHANGELOG.rst b/common/autoware_component_interface_specs/CHANGELOG.rst index faacc0cfdb2bf..43590966602d2 100644 --- a/common/autoware_component_interface_specs/CHANGELOG.rst +++ b/common/autoware_component_interface_specs/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_component_interface_specs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_component_interface_specs/package.xml b/common/autoware_component_interface_specs/package.xml index 5a2fd993613d1..4bbe62e7e9701 100644 --- a/common/autoware_component_interface_specs/package.xml +++ b/common/autoware_component_interface_specs/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_specs - 0.39.0 + 0.40.0 The autoware_component_interface_specs package Takagi, Isamu Yukihiro Saito diff --git a/common/autoware_component_interface_tools/CHANGELOG.rst b/common/autoware_component_interface_tools/CHANGELOG.rst index e0c07efa43418..b17fa431b27bb 100644 --- a/common/autoware_component_interface_tools/CHANGELOG.rst +++ b/common/autoware_component_interface_tools/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_component_interface_tools ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix: fix missing namespaces in C++ code (`#9477 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_component_interface_tools/package.xml b/common/autoware_component_interface_tools/package.xml index d0c79f3ad0d67..e38b048e22ebe 100644 --- a/common/autoware_component_interface_tools/package.xml +++ b/common/autoware_component_interface_tools/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_tools - 0.39.0 + 0.40.0 The autoware_component_interface_tools package Takagi, Isamu Apache License 2.0 diff --git a/common/autoware_component_interface_utils/CHANGELOG.rst b/common/autoware_component_interface_utils/CHANGELOG.rst index 6e6ee88a3f3a7..d19e72f19e469 100644 --- a/common/autoware_component_interface_utils/CHANGELOG.rst +++ b/common/autoware_component_interface_utils/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_component_interface_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* fix: fix package names in changelog files (`#9500 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/common/autoware_component_interface_utils/package.xml b/common/autoware_component_interface_utils/package.xml index 5efebf5c0d210..0bc51ee211d50 100755 --- a/common/autoware_component_interface_utils/package.xml +++ b/common/autoware_component_interface_utils/package.xml @@ -2,7 +2,7 @@ autoware_component_interface_utils - 0.39.0 + 0.40.0 The autoware_component_interface_utils package Takagi, Isamu Yukihiro Saito diff --git a/common/autoware_fake_test_node/CHANGELOG.rst b/common/autoware_fake_test_node/CHANGELOG.rst index 5f04908a8ab0f..5bc3669a5aa27 100644 --- a/common/autoware_fake_test_node/CHANGELOG.rst +++ b/common/autoware_fake_test_node/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package autoware_fake_test_node ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix package names in changelog files (`#9500 `_) +* refactor(fake_test_node): prefix package and namespace with autoware (`#9249 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_fake_test_node/package.xml b/common/autoware_fake_test_node/package.xml index 531e9351023e6..0ae881e4a41ba 100644 --- a/common/autoware_fake_test_node/package.xml +++ b/common/autoware_fake_test_node/package.xml @@ -2,7 +2,7 @@ autoware_fake_test_node - 0.39.0 + 0.40.0 A fake node that we can use in the integration-like cpp tests. Apex.AI, Inc. Tomoya Kimura diff --git a/common/autoware_global_parameter_loader/CHANGELOG.rst b/common/autoware_global_parameter_loader/CHANGELOG.rst index 2de0adf89cb3e..d778018320271 100644 --- a/common/autoware_global_parameter_loader/CHANGELOG.rst +++ b/common/autoware_global_parameter_loader/CHANGELOG.rst @@ -2,6 +2,20 @@ Changelog for package global_parameter_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* refactor(global_parameter_loader): prefix package and namespace with autoware (`#9303 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_global_parameter_loader/package.xml b/common/autoware_global_parameter_loader/package.xml index ef40ff8df22aa..8238e5852284f 100644 --- a/common/autoware_global_parameter_loader/package.xml +++ b/common/autoware_global_parameter_loader/package.xml @@ -2,7 +2,7 @@ autoware_global_parameter_loader - 0.39.0 + 0.40.0 The autoware_global_parameter_loader package Ryohsuke Mitsudome Apache License 2.0 diff --git a/common/autoware_glog_component/CHANGELOG.rst b/common/autoware_glog_component/CHANGELOG.rst index 66eee038b6353..e9176b6524049 100644 --- a/common/autoware_glog_component/CHANGELOG.rst +++ b/common/autoware_glog_component/CHANGELOG.rst @@ -2,6 +2,21 @@ Changelog for package glog_component ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* refactor(glog_component): prefix package and namespace with autoware (`#9302 `_) + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_glog_component/package.xml b/common/autoware_glog_component/package.xml index 3bfb6c97155b0..eab95fa8944d3 100644 --- a/common/autoware_glog_component/package.xml +++ b/common/autoware_glog_component/package.xml @@ -2,7 +2,7 @@ autoware_glog_component - 0.39.0 + 0.40.0 The autoware_glog_component package Takamasa Horibe Apache License 2.0 diff --git a/common/autoware_goal_distance_calculator/CHANGELOG.rst b/common/autoware_goal_distance_calculator/CHANGELOG.rst index 45fa8825612ef..df190270e02ab 100644 --- a/common/autoware_goal_distance_calculator/CHANGELOG.rst +++ b/common/autoware_goal_distance_calculator/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_goal_distance_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_goal_distance_calculator/package.xml b/common/autoware_goal_distance_calculator/package.xml index 24b3b2f2ba9c6..903d77515f262 100644 --- a/common/autoware_goal_distance_calculator/package.xml +++ b/common/autoware_goal_distance_calculator/package.xml @@ -2,7 +2,7 @@ autoware_goal_distance_calculator - 0.39.0 + 0.40.0 The autoware_goal_distance_calculator package Taiki Tanaka Apache License 2.0 diff --git a/common/autoware_grid_map_utils/CHANGELOG.rst b/common/autoware_grid_map_utils/CHANGELOG.rst index 31df087b80d59..7a1b19b90a958 100644 --- a/common/autoware_grid_map_utils/CHANGELOG.rst +++ b/common/autoware_grid_map_utils/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_grid_map_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_grid_map_utils/package.xml b/common/autoware_grid_map_utils/package.xml index cc64daa0045e0..bf89abc507173 100644 --- a/common/autoware_grid_map_utils/package.xml +++ b/common/autoware_grid_map_utils/package.xml @@ -2,7 +2,7 @@ autoware_grid_map_utils - 0.39.0 + 0.40.0 Utilities for the grid_map library Maxime CLEMENT Apache License 2.0 diff --git a/common/autoware_interpolation/CHANGELOG.rst b/common/autoware_interpolation/CHANGELOG.rst index e62e73ae4ec21..37fc48c525a49 100644 --- a/common/autoware_interpolation/CHANGELOG.rst +++ b/common/autoware_interpolation/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_interpolation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_interpolation/package.xml b/common/autoware_interpolation/package.xml index 22db75271b316..3bad757405ed4 100644 --- a/common/autoware_interpolation/package.xml +++ b/common/autoware_interpolation/package.xml @@ -2,7 +2,7 @@ autoware_interpolation - 0.39.0 + 0.40.0 The spline interpolation package Fumiya Watanabe Takayuki Murooka diff --git a/common/autoware_kalman_filter/CHANGELOG.rst b/common/autoware_kalman_filter/CHANGELOG.rst index 5ec0bcc9e72dc..a7e68f8843e74 100644 --- a/common/autoware_kalman_filter/CHANGELOG.rst +++ b/common/autoware_kalman_filter/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_kalman_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_kalman_filter/package.xml b/common/autoware_kalman_filter/package.xml index 4cd94ff488899..e51bb06e9de43 100644 --- a/common/autoware_kalman_filter/package.xml +++ b/common/autoware_kalman_filter/package.xml @@ -2,7 +2,7 @@ autoware_kalman_filter - 0.39.0 + 0.40.0 The kalman filter package Yukihiro Saito Takeshi Ishita diff --git a/common/autoware_motion_utils/CHANGELOG.rst b/common/autoware_motion_utils/CHANGELOG.rst index 216d4d978bd8a..187ddda4acd39 100644 --- a/common/autoware_motion_utils/CHANGELOG.rst +++ b/common/autoware_motion_utils/CHANGELOG.rst @@ -2,6 +2,75 @@ Changelog for package autoware_motion_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(factor): move steering factor interface to motion utils (`#9337 `_) +* feat(behavior_velocity_stop_line): replace autoware_motion_utils to autoware_trajectory (`#9299 `_) + * feat(behavior_velocity_stop_line): replace autoware_motion_utils to autoware_trajectory + * update + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(autoware_trajectory): move trajectory_container from autoware_motion_utils to a new package (`#9253 `_) + * create trajectory container package + * update + * update + * style(pre-commit): autofix + * update codeowner + * update + * fix cmake + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat(autoware_motion_utils): add new trajectory class (`#8693 `_) + * feat(autoware_motion_utils): add interpolator + * use int32_t instead of int + * use int32_t instead of int + * use int32_t instead of int + * add const as much as possible and use `at()` in `vector` + * fix directory name + * refactor code and add example + * update + * remove unused include + * refactor code + * add clone function + * fix stairstep + * make constructor to public + * feat(autoware_motion_utils): add trajectory class + * Update CMakeLists.txt + * fix + * fix package.xml + * update crop + * revert crtp change + * update package.xml + * updating... + * update + * solve build problem + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/common/autoware_motion_utils/package.xml b/common/autoware_motion_utils/package.xml index 4aa215b48e2ce..029985a53f020 100644 --- a/common/autoware_motion_utils/package.xml +++ b/common/autoware_motion_utils/package.xml @@ -2,7 +2,7 @@ autoware_motion_utils - 0.39.0 + 0.40.0 The autoware_motion_utils package Satoshi Ota Takayuki Murooka diff --git a/common/autoware_object_recognition_utils/CHANGELOG.rst b/common/autoware_object_recognition_utils/CHANGELOG.rst index 44bc2573f435a..920106de22082 100644 --- a/common/autoware_object_recognition_utils/CHANGELOG.rst +++ b/common/autoware_object_recognition_utils/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_object_recognition_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_object_recognition_utils/package.xml b/common/autoware_object_recognition_utils/package.xml index 729999f96dc6e..05327766008f2 100644 --- a/common/autoware_object_recognition_utils/package.xml +++ b/common/autoware_object_recognition_utils/package.xml @@ -2,7 +2,7 @@ autoware_object_recognition_utils - 0.39.0 + 0.40.0 The autoware_object_recognition_utils package Takayuki Murooka Shunsuke Miura diff --git a/common/autoware_osqp_interface/CHANGELOG.rst b/common/autoware_osqp_interface/CHANGELOG.rst index 5ce7b02250fda..d400b77f4bf61 100644 --- a/common/autoware_osqp_interface/CHANGELOG.rst +++ b/common/autoware_osqp_interface/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_osqp_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* fix(autoware_osqp_interface): fix clang-tidy errors (`#9440 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_osqp_interface/package.xml b/common/autoware_osqp_interface/package.xml index 95ffebe833cc6..92a2afeccc4e0 100644 --- a/common/autoware_osqp_interface/package.xml +++ b/common/autoware_osqp_interface/package.xml @@ -2,7 +2,7 @@ autoware_osqp_interface - 0.39.0 + 0.40.0 Interface for the OSQP solver Maxime CLEMENT Takayuki Murooka diff --git a/common/autoware_path_distance_calculator/CHANGELOG.rst b/common/autoware_path_distance_calculator/CHANGELOG.rst index 6adf0a3e3c851..cd4c6ae5ce49b 100644 --- a/common/autoware_path_distance_calculator/CHANGELOG.rst +++ b/common/autoware_path_distance_calculator/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_path_distance_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_path_distance_calculator/package.xml b/common/autoware_path_distance_calculator/package.xml index 7466b299e7e2e..6d207f6ed795d 100644 --- a/common/autoware_path_distance_calculator/package.xml +++ b/common/autoware_path_distance_calculator/package.xml @@ -2,7 +2,7 @@ autoware_path_distance_calculator - 0.39.0 + 0.40.0 The autoware_path_distance_calculator package Takagi, Isamu Apache License 2.0 diff --git a/common/autoware_point_types/CHANGELOG.rst b/common/autoware_point_types/CHANGELOG.rst index 12cef4043ae3e..5e26002677a36 100644 --- a/common/autoware_point_types/CHANGELOG.rst +++ b/common/autoware_point_types/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_point_types ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_point_types/package.xml b/common/autoware_point_types/package.xml index fd48c12daa2e9..e35e6a63de648 100644 --- a/common/autoware_point_types/package.xml +++ b/common/autoware_point_types/package.xml @@ -2,7 +2,7 @@ autoware_point_types - 0.39.0 + 0.40.0 The point types definition to use point_cloud_msg_wrapper David Wong Max Schmeller diff --git a/common/autoware_polar_grid/CHANGELOG.rst b/common/autoware_polar_grid/CHANGELOG.rst index b4e9e612fe093..72a53e6cef4b7 100644 --- a/common/autoware_polar_grid/CHANGELOG.rst +++ b/common/autoware_polar_grid/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_polar_grid ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_polar_grid/package.xml b/common/autoware_polar_grid/package.xml index a2ed7a138bdca..16d6a72985ec9 100644 --- a/common/autoware_polar_grid/package.xml +++ b/common/autoware_polar_grid/package.xml @@ -2,7 +2,7 @@ autoware_polar_grid - 0.39.0 + 0.40.0 The autoware_polar_grid package Yukihiro Saito Apache License 2.0 diff --git a/common/autoware_pyplot/CHANGELOG.rst b/common/autoware_pyplot/CHANGELOG.rst new file mode 100644 index 0000000000000..c3b1f9c17f7d5 --- /dev/null +++ b/common/autoware_pyplot/CHANGELOG.rst @@ -0,0 +1,39 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_pyplot +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* docs(autoware_pyplot): add missing readme and move the package to common (`#9546 `_) +* fix(autoware_pyplot): fix missing python3-dev dependency (`#9461 `_) +* feat(pyplot): add C++ pyplot (`#9430 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Mamoru Sobue, Ryohsuke Mitsudome + +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* docs(autoware_pyplot): add missing readme and move the package to common (`#9546 `_) +* fix(autoware_pyplot): fix missing python3-dev dependency (`#9461 `_) +* feat(pyplot): add C++ pyplot (`#9430 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Mamoru Sobue, Ryohsuke Mitsudome + +0.39.0 (2024-11-25) +------------------- + +0.38.0 (2024-11-11) +------------------- diff --git a/common/autoware_pyplot/package.xml b/common/autoware_pyplot/package.xml index 297ab68cb9367..2f3f3014d4907 100644 --- a/common/autoware_pyplot/package.xml +++ b/common/autoware_pyplot/package.xml @@ -2,12 +2,11 @@ autoware_pyplot - 0.39.0 + 0.40.0 C++ interface for matplotlib based on pybind11 Mamoru Sobue Yukinari Hisaki Apache License 2.0 - Koji Minoda Mamoru Sobue diff --git a/common/autoware_qp_interface/CHANGELOG.rst b/common/autoware_qp_interface/CHANGELOG.rst index ce931f6f5e1e7..f76dac861e1e6 100644 --- a/common/autoware_qp_interface/CHANGELOG.rst +++ b/common/autoware_qp_interface/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_qp_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* fix: fix package names in changelog files (`#9500 `_) +* fix(autoware_osqp_interface): fix clang-tidy errors (`#9440 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/common/autoware_qp_interface/package.xml b/common/autoware_qp_interface/package.xml index 5bd3ce1ad8464..b61d03a36db72 100644 --- a/common/autoware_qp_interface/package.xml +++ b/common/autoware_qp_interface/package.xml @@ -2,7 +2,7 @@ autoware_qp_interface - 0.39.0 + 0.40.0 Interface for the QP solvers Takayuki Murooka Fumiya Watanabe diff --git a/common/autoware_signal_processing/CHANGELOG.rst b/common/autoware_signal_processing/CHANGELOG.rst index f41732a258cf7..b5b01e98e23a7 100644 --- a/common/autoware_signal_processing/CHANGELOG.rst +++ b/common/autoware_signal_processing/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_signal_processing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_signal_processing/package.xml b/common/autoware_signal_processing/package.xml index 6197c641a6f82..b8d7c064112dd 100644 --- a/common/autoware_signal_processing/package.xml +++ b/common/autoware_signal_processing/package.xml @@ -2,7 +2,7 @@ autoware_signal_processing - 0.39.0 + 0.40.0 The signal processing package Takayuki Murooka Takamasa Horibe diff --git a/common/autoware_test_utils/CHANGELOG.rst b/common/autoware_test_utils/CHANGELOG.rst index 02a046a20e595..950fdb09aa119 100644 --- a/common/autoware_test_utils/CHANGELOG.rst +++ b/common/autoware_test_utils/CHANGELOG.rst @@ -2,6 +2,58 @@ Changelog for package autoware_test_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* ci(pre-commit): update cpplint to 2.0.0 (`#9557 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* refactor(test_utils): return parser as optional (`#9391 `_) + Co-authored-by: Mamoru Sobue +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(autoware_test_utils): add parser for LaneletRoute, TrackedObject (`#9317 `_) +* test(autoware_test_utils): add TrafficLight to map, fix launcher (`#9318 `_) +* test(bpp_common): add tests for the static drivable area (`#9324 `_) +* test(costmap_generator): unit test implementation for costmap generator (`#9149 `_) + * modify costmap generator directory structure + * rename class CostmapGenerator to CostmapGeneratorNode + * unit test for object_map_utils + * catch error from lookupTransform + * use polling subscriber in costmap generator node + * add test for costmap generator node + * add test for isActive() + * revert unnecessary changes + * remove commented out line + * minor fix + * Update planning/autoware_costmap_generator/src/costmap_generator.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(autoware_test_utils): use sample_vehicle/sample_sensor_kit (`#9290 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(autoware_test_utils): add general topic dumper (`#9207 `_) +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* feat(autoware_test_utils): add traffic light msgs parser (`#9177 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Maxime CLEMENT, Ryohsuke Mitsudome, Yutaka Kondo, Zulfaqar Azmi, awf-autoware-bot[bot], mkquda + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/common/autoware_test_utils/package.xml b/common/autoware_test_utils/package.xml index 97c81c62ba512..22572abb72b69 100644 --- a/common/autoware_test_utils/package.xml +++ b/common/autoware_test_utils/package.xml @@ -2,7 +2,7 @@ autoware_test_utils - 0.39.0 + 0.40.0 ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara Takamasa Horibe diff --git a/common/autoware_testing/CHANGELOG.rst b/common/autoware_testing/CHANGELOG.rst index 1a016888fda47..09ff6bdc4cf04 100644 --- a/common/autoware_testing/CHANGELOG.rst +++ b/common/autoware_testing/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_testing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_testing/package.xml b/common/autoware_testing/package.xml index ae5b5e7a5d466..a5df1302b682d 100644 --- a/common/autoware_testing/package.xml +++ b/common/autoware_testing/package.xml @@ -2,7 +2,7 @@ autoware_testing - 0.39.0 + 0.40.0 Tools for handling standard tests based on ros_testing Adam Dabrowski Tomoya Kimura diff --git a/common/autoware_time_utils/CHANGELOG.rst b/common/autoware_time_utils/CHANGELOG.rst index 4f0f87e5daad8..b18c3dd42cbc6 100644 --- a/common/autoware_time_utils/CHANGELOG.rst +++ b/common/autoware_time_utils/CHANGELOG.rst @@ -2,6 +2,38 @@ Changelog for package autoware_time_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix: fix package names in changelog files (`#9500 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(time_utils): prefix package and namespace with autoware (`#9173 `_) + * refactor(time_utils): prefix package and namespace with autoware + * refactor(time_utils): prefix package and namespace with autoware + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/common/autoware_time_utils/package.xml b/common/autoware_time_utils/package.xml index 6491006b6cc27..278143e9ac4f8 100644 --- a/common/autoware_time_utils/package.xml +++ b/common/autoware_time_utils/package.xml @@ -2,7 +2,7 @@ autoware_time_utils - 0.39.0 + 0.40.0 Simple conversion methods to/from std::chrono to simplify algorithm development Christopher Ho Tomoya Kimura diff --git a/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst index ea5339ba8d566..27a61bf71b1e8 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst +++ b/common/autoware_traffic_light_recognition_marker_publisher/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package autoware_traffic_light_recognition_marker_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix(cpplint): include what you use - common (`#9564 `_) +* fix: fix package names in changelog files (`#9500 `_) +* fix: fix missing namespaces in C++ code (`#9477 `_) +* refactor(traffic_light_recognition_marker_publisher): prefix package and namespace with autoware (`#9305 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_traffic_light_recognition_marker_publisher/package.xml b/common/autoware_traffic_light_recognition_marker_publisher/package.xml index ddca8ad56c281..af670dc19baf1 100644 --- a/common/autoware_traffic_light_recognition_marker_publisher/package.xml +++ b/common/autoware_traffic_light_recognition_marker_publisher/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_recognition_marker_publisher - 0.39.0 + 0.40.0 The autoware_traffic_light_recognition_marker_publisher package Tomoya Kimura Takeshi Miura diff --git a/common/autoware_traffic_light_utils/CHANGELOG.rst b/common/autoware_traffic_light_utils/CHANGELOG.rst index 518123e826992..0230e43574de8 100644 --- a/common/autoware_traffic_light_utils/CHANGELOG.rst +++ b/common/autoware_traffic_light_utils/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package autoware_traffic_light_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix(cpplint): include what you use - common (`#9564 `_) +* fix: fix package names in changelog files (`#9500 `_) +* refactor(traffic_light_utils): prefix package and namespace with autoware (`#9251 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_traffic_light_utils/package.xml b/common/autoware_traffic_light_utils/package.xml index 744a7b08c22a9..645e92e2d992f 100644 --- a/common/autoware_traffic_light_utils/package.xml +++ b/common/autoware_traffic_light_utils/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_utils - 0.39.0 + 0.40.0 The autoware_traffic_light_utils package Kotaro Uetake Shunsuke Miura diff --git a/common/autoware_trajectory/CHANGELOG.rst b/common/autoware_trajectory/CHANGELOG.rst index 1fbf18ec57abe..307dd8eb3dcf5 100644 --- a/common/autoware_trajectory/CHANGELOG.rst +++ b/common/autoware_trajectory/CHANGELOG.rst @@ -2,6 +2,49 @@ Changelog for package autoware_trajectory ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* refactor: correct spelling (`#9528 `_) +* fix(autoware_trajectory): autoware_trajectory bug (`#9475 `_) + fix autoware_trajectory bug +* 0.39.0 +* fix version +* update changelog +* add changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* refactor(autoware_trajectory): refactor autoware_trajectory (`#9356 `_) +* feat(behavior_velocity_stop_line): replace autoware_motion_utils to autoware_trajectory (`#9299 `_) + * feat(behavior_velocity_stop_line): replace autoware_motion_utils to autoware_trajectory + * update + --------- +* feat(autoware_trajectory): change default value of min_points (`#9315 `_) +* fix(autoware_trajectory): fix bug of autoware_trajectory (`#9314 `_) +* feat(autoware_trajectory): change interface of InterpolatedArray (`#9264 `_) + change interface of InterpolateArray +* feat(autoware_trajectory): move trajectory_container from autoware_motion_utils to a new package (`#9253 `_) + * create trajectory container package + * update + * update + * style(pre-commit): autofix + * update codeowner + * update + * fix cmake + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * add changelog diff --git a/common/autoware_trajectory/package.xml b/common/autoware_trajectory/package.xml index b1aaaed7efc6b..eaa5fca80ff46 100644 --- a/common/autoware_trajectory/package.xml +++ b/common/autoware_trajectory/package.xml @@ -2,7 +2,7 @@ autoware_trajectory - 0.39.0 + 0.40.0 The autoware_trajectory package Yukinari Hisaki Takayuki Murooka diff --git a/common/autoware_universe_utils/CHANGELOG.rst b/common/autoware_universe_utils/CHANGELOG.rst index c85a9f14e960e..31f45a8ecbfce 100644 --- a/common/autoware_universe_utils/CHANGELOG.rst +++ b/common/autoware_universe_utils/CHANGELOG.rst @@ -2,6 +2,48 @@ Changelog for package autoware_universe_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* feat(universe_utils): add extra info to time keeper warning (`#9484 `_) + add extra info to time keeper warning +* refactor(evaluators, autoware_universe_utils): rename Stat class to Accumulator and move it to autoware_universe_utils (`#9459 `_) + * add Accumulator class to autoware_universe_utils + * use Accumulator on all evaluators. + * pre-commit + * found and fixed a bug. add more tests. + * pre-commit + * Update common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_utils): address self-intersecting polygons in random_concave_generator and handle empty inners() during triangulation (`#8995 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Giovanni Muhammad Raditya, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, danielsanchezaran + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/common/autoware_universe_utils/package.xml b/common/autoware_universe_utils/package.xml index 1c2e9993439e4..d04e1a57e78ab 100644 --- a/common/autoware_universe_utils/package.xml +++ b/common/autoware_universe_utils/package.xml @@ -2,7 +2,7 @@ autoware_universe_utils - 0.39.0 + 0.40.0 The autoware_universe_utils package Takamasa Horibe Takayuki Murooka diff --git a/common/autoware_vehicle_info_utils/CHANGELOG.rst b/common/autoware_vehicle_info_utils/CHANGELOG.rst index 4d76f469414b5..a02256d5f9cea 100644 --- a/common/autoware_vehicle_info_utils/CHANGELOG.rst +++ b/common/autoware_vehicle_info_utils/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_vehicle_info_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix(static_centerline_generator): several bug fixes (`#9426 `_) + * fix: dependent packages + * feat: use steer angle, use warn for steer angle failure, calc curvature dicontinuously + * fix cppcheck + --------- +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - common (`#9564 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Takayuki Murooka, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/autoware_vehicle_info_utils/package.xml b/common/autoware_vehicle_info_utils/package.xml index bc3f12f5f3ca0..b6a2f1ad5154a 100644 --- a/common/autoware_vehicle_info_utils/package.xml +++ b/common/autoware_vehicle_info_utils/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_info_utils - 0.39.0 + 0.40.0 The autoware_vehicle_info_utils package diff --git a/common/tier4_api_utils/CHANGELOG.rst b/common/tier4_api_utils/CHANGELOG.rst index a6ac6f3cf1e86..d9b94eeacc79b 100644 --- a/common/tier4_api_utils/CHANGELOG.rst +++ b/common/tier4_api_utils/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_api_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/common/tier4_api_utils/package.xml b/common/tier4_api_utils/package.xml index dba6450a338e4..3e7f99b8736c5 100644 --- a/common/tier4_api_utils/package.xml +++ b/common/tier4_api_utils/package.xml @@ -2,7 +2,7 @@ tier4_api_utils - 0.39.0 + 0.40.0 The tier4_api_utils package Takagi, Isamu Apache License 2.0 diff --git a/control/autoware_autonomous_emergency_braking/CHANGELOG.rst b/control/autoware_autonomous_emergency_braking/CHANGELOG.rst index 67fe12fb1243b..578ffc14bae84 100644 --- a/control/autoware_autonomous_emergency_braking/CHANGELOG.rst +++ b/control/autoware_autonomous_emergency_braking/CHANGELOG.rst @@ -2,6 +2,89 @@ Changelog for package autoware_autonomous_emergency_braking ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(autoware_autonomous_emergency_braking): add package maintainer (`#9580 `_) + add package maintainer +* fix(cpplint): include what you use - control (`#9565 `_) +* refactor(autoware_autonomous_emergency_braking): update longitudinal offset parameter name (`#9463 `_) + Update the parameter name for the longitudinal offset distance used for collision check in the autonomous emergency braking control module. The parameter name has been changed from "longitudinal_offset" to "longitudinal_offset_margin" to better reflect its purpose. +* refactor(autoware_autonomous_emergency_braking): add getObjectOnPathData and getLongitudinalOffset functions (`#9462 `_) + * feat(aeb): add getObjectOnPathData and getLongitudinalOffset functions + --------- +* docs(autoware_autonomous_emergency_braking): enhance IMU path generation section with constraints and algorithm details (`#9458 `_) +* feat(autonomous_emergency_braking): set a lateral deviation limit for AEB IMU path (`#9410 `_) + * add a steer limit option for AEB + * wip refactor and add max lat dev param + * fix issue with test + * delete unwanted parts + * delete unwanted changes + * set to false + * change back path length + * add suggestions + * update readme + * cpp check + * fix some sentences + * expand explanation + * update image + * update README + * update description + * fix typo + * fix sentences + * improve readme + --------- +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(control): missing dependency in control components (`#9073 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autonomous_emergency_braking): solve issue with arc length (`#9247 `_) + * solve issue with arc length + * fix problem with points one vehicle apart from path + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), Kyoichi Sugahara, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, danielsanchezaran, mkquda, ぐるぐる + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_autonomous_emergency_braking/package.xml b/control/autoware_autonomous_emergency_braking/package.xml index bab41a7c634d2..e22a0f099e2f0 100644 --- a/control/autoware_autonomous_emergency_braking/package.xml +++ b/control/autoware_autonomous_emergency_braking/package.xml @@ -2,7 +2,7 @@ autoware_autonomous_emergency_braking - 0.39.0 + 0.40.0 Autonomous Emergency Braking package as a ROS 2 node Takamasa Horibe Tomoya Kimura diff --git a/control/autoware_collision_detector/CHANGELOG.rst b/control/autoware_collision_detector/CHANGELOG.rst index 4d0f2f9b2c579..a108327961ac3 100644 --- a/control/autoware_collision_detector/CHANGELOG.rst +++ b/control/autoware_collision_detector/CHANGELOG.rst @@ -2,6 +2,40 @@ Changelog for package autoware_collision_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(collision_detector): skip process when odometry is not published (`#9308 `_) + * subscribe odometry + * fix precommit + * remove unnecessary log info + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(collision_detector): use polling subscriber (`#9213 `_) + use polling subscriber +* Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_collision_detector/package.xml b/control/autoware_collision_detector/package.xml index e2bdeb7fa9250..680c20b8094e7 100644 --- a/control/autoware_collision_detector/package.xml +++ b/control/autoware_collision_detector/package.xml @@ -2,7 +2,7 @@ autoware_collision_detector - 0.39.0 + 0.40.0 The collision_detector package Kyoichi Sugahara diff --git a/control/autoware_control_validator/CHANGELOG.rst b/control/autoware_control_validator/CHANGELOG.rst index fca1ed1e51184..c35ece2151697 100644 --- a/control/autoware_control_validator/CHANGELOG.rst +++ b/control/autoware_control_validator/CHANGELOG.rst @@ -2,6 +2,36 @@ Changelog for package autoware_control_validator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat: suppress warning/error of the empty predicted trajectory by MPC (`#9373 `_) +* fix(autoware_control_validator): fix clang-diagnostic-unused-private-field (`#9381 `_) +* fix(control): missing dependency in control components (`#9073 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Takayuki Murooka, Yutaka Kondo, ぐるぐる + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_control_validator/package.xml b/control/autoware_control_validator/package.xml index 24c3daebb6749..fbaa3f013b64e 100644 --- a/control/autoware_control_validator/package.xml +++ b/control/autoware_control_validator/package.xml @@ -2,7 +2,7 @@ autoware_control_validator - 0.39.0 + 0.40.0 ros node for autoware_control_validator Kyoichi Sugahara Takamasa Horibe diff --git a/control/autoware_external_cmd_selector/CHANGELOG.rst b/control/autoware_external_cmd_selector/CHANGELOG.rst index 85e6e33fae450..2e4ee4c7d2906 100644 --- a/control/autoware_external_cmd_selector/CHANGELOG.rst +++ b/control/autoware_external_cmd_selector/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_external_cmd_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/control/autoware_external_cmd_selector/package.xml b/control/autoware_external_cmd_selector/package.xml index 036e293b308df..86cbdf9f00bfb 100644 --- a/control/autoware_external_cmd_selector/package.xml +++ b/control/autoware_external_cmd_selector/package.xml @@ -2,7 +2,7 @@ autoware_external_cmd_selector - 0.39.0 + 0.40.0 The autoware_external_cmd_selector package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_joy_controller/CHANGELOG.rst b/control/autoware_joy_controller/CHANGELOG.rst index f0ce6cd9eb030..8d25bab7fc6db 100644 --- a/control/autoware_joy_controller/CHANGELOG.rst +++ b/control/autoware_joy_controller/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_joy_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/control/autoware_joy_controller/package.xml b/control/autoware_joy_controller/package.xml index 3d695f995f855..b178ec167306a 100644 --- a/control/autoware_joy_controller/package.xml +++ b/control/autoware_joy_controller/package.xml @@ -2,7 +2,7 @@ autoware_joy_controller - 0.39.0 + 0.40.0 The autoware_joy_controller package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_lane_departure_checker/CHANGELOG.rst b/control/autoware_lane_departure_checker/CHANGELOG.rst index d7f502990a9a2..9b49f0c6c8fb1 100644 --- a/control/autoware_lane_departure_checker/CHANGELOG.rst +++ b/control/autoware_lane_departure_checker/CHANGELOG.rst @@ -2,6 +2,50 @@ Changelog for package autoware_lane_departure_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* ci(pre-commit): update cpplint to 2.0.0 (`#9557 `_) +* test(lane_departure_checker): add unit test for createVehiclePassingAreas (`#9548 `_) + * test(lane_departure_checker): add unit tests for createVehiclePassingAreas function + --------- +* refactor(lane_departure_checker): move member functions to util functions (`#9547 `_) + * refactor(lane_departure_checker): move member functions to util functions + --------- +* fix(cpplint): include what you use - control (`#9565 `_) +* test(lane_departure_checker): add tests for calcTrajectoryDeviation(), calcMaxSearchLengthForBoundaries() (`#9029 `_) + * move calcTrajectoryDeviation() to separate files + * move calcMaxSearchLengthForBoundaries() to separate files + * add tests for calcTrajectoryDeviation() + * add tests for calcMaxSearchLengthForBoundaries() + --------- + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat: suppress warning/error of the empty predicted trajectory by MPC (`#9373 `_) +* feat(start_planner, lane_departure_checker): speed up by updating polygons (`#9309 `_) + speed up by updating polygons +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kyoichi Sugahara, M. Fatih Cırıt, Mitsuhiro Sakamoto, Ryohsuke Mitsudome, Takayuki Murooka, Yutaka Kondo, awf-autoware-bot[bot], danielsanchezaran + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_lane_departure_checker/package.xml b/control/autoware_lane_departure_checker/package.xml index 70ea7459a2b93..2689b4a4dbcb7 100644 --- a/control/autoware_lane_departure_checker/package.xml +++ b/control/autoware_lane_departure_checker/package.xml @@ -2,7 +2,7 @@ autoware_lane_departure_checker - 0.39.0 + 0.40.0 The autoware_lane_departure_checker package Kyoichi Sugahara Makoto Kurihara diff --git a/control/autoware_mpc_lateral_controller/CHANGELOG.rst b/control/autoware_mpc_lateral_controller/CHANGELOG.rst index a361c3aaec161..f149921648e8d 100644 --- a/control/autoware_mpc_lateral_controller/CHANGELOG.rst +++ b/control/autoware_mpc_lateral_controller/CHANGELOG.rst @@ -2,6 +2,56 @@ Changelog for package autoware_mpc_lateral_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* fix(autoware_mpc_lateral_controller): fix clang-tidy errors (`#9436 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(mpc_lateral_controller): suppress rclcpp_warning/error (`#9382 `_) + * feat(mpc_lateral_controller): suppress rclcpp_warning/error + * fix + * fix test + --------- +* fix(autoware_mpc_lateral_controller): fix variableScope (`#9390 `_) +* feat: suppress warning/error of the empty predicted trajectory by MPC (`#9373 `_) +* chore(autoware_mpc_lateral_controller): add maintainer (`#9374 `_) +* feat(trajectory_follower): publsih control horzion (`#8977 `_) + * feat(trajectory_follower): publsih control horzion + * fix typo + * rename functions and minor refactor + * add option to enable horizon pub + * add tests for horizon + * update docs + * rename to ~/debug/control_cmd_horizon + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_mpc_lateral_controller): fix bugprone-misplaced-widening-cast (`#9224 `_) + * fix: bugprone-misplaced-widening-cast + * fix: consider negative values + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(mpc_lateral_controller): correctly resample the MPC trajectory yaws (`#9199 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, Kyoichi Sugahara, M. Fatih Cırıt, Maxime CLEMENT, Ryohsuke Mitsudome, Ryuta Kambe, Takayuki Murooka, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_mpc_lateral_controller/package.xml b/control/autoware_mpc_lateral_controller/package.xml index d8bb14d211bf8..b450af05ea0e1 100644 --- a/control/autoware_mpc_lateral_controller/package.xml +++ b/control/autoware_mpc_lateral_controller/package.xml @@ -2,7 +2,7 @@ autoware_mpc_lateral_controller - 0.39.0 + 0.40.0 MPC-based lateral controller Takamasa Horibe diff --git a/control/autoware_obstacle_collision_checker/CHANGELOG.rst b/control/autoware_obstacle_collision_checker/CHANGELOG.rst index 05e5b2d4190d7..79a7b2d8819e4 100644 --- a/control/autoware_obstacle_collision_checker/CHANGELOG.rst +++ b/control/autoware_obstacle_collision_checker/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_obstacle_collision_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/control/autoware_obstacle_collision_checker/package.xml b/control/autoware_obstacle_collision_checker/package.xml index 66df5e98bf57d..334c6d970fc36 100644 --- a/control/autoware_obstacle_collision_checker/package.xml +++ b/control/autoware_obstacle_collision_checker/package.xml @@ -2,7 +2,7 @@ autoware_obstacle_collision_checker - 0.39.0 + 0.40.0 The obstacle_collision_checker package Taiki Tanaka Tomoya Kimura diff --git a/control/autoware_operation_mode_transition_manager/CHANGELOG.rst b/control/autoware_operation_mode_transition_manager/CHANGELOG.rst index af99c3781459a..3f178c04f9d48 100644 --- a/control/autoware_operation_mode_transition_manager/CHANGELOG.rst +++ b/control/autoware_operation_mode_transition_manager/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_operation_mode_transition_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_operation_mode_transition_manager/package.xml b/control/autoware_operation_mode_transition_manager/package.xml index 7a0d6977a3e8f..eb4d50b625f11 100644 --- a/control/autoware_operation_mode_transition_manager/package.xml +++ b/control/autoware_operation_mode_transition_manager/package.xml @@ -1,6 +1,6 @@ autoware_operation_mode_transition_manager - 0.39.0 + 0.40.0 The operation_mode_transition_manager package Takamasa Horibe Tomoya Kimura diff --git a/control/autoware_pid_longitudinal_controller/CHANGELOG.rst b/control/autoware_pid_longitudinal_controller/CHANGELOG.rst index 57e2ce30aff35..d63f075c26918 100644 --- a/control/autoware_pid_longitudinal_controller/CHANGELOG.rst +++ b/control/autoware_pid_longitudinal_controller/CHANGELOG.rst @@ -2,6 +2,45 @@ Changelog for package autoware_pid_longitudinal_controller ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(pid_longitudinal_controller): suppress rclcpp_warning/error (`#9384 `_) + * feat(pid_longitudinal_controller): suppress rclcpp_warning/error + * update codeowner + --------- +* feat(trajectory_follower): publsih control horzion (`#8977 `_) + * feat(trajectory_follower): publsih control horzion + * fix typo + * rename functions and minor refactor + * add option to enable horizon pub + * add tests for horizon + * update docs + * rename to ~/debug/control_cmd_horizon + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Takayuki Murooka, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/control/autoware_pid_longitudinal_controller/package.xml b/control/autoware_pid_longitudinal_controller/package.xml index 88f8abaf225e8..67e95a9d4c0ac 100644 --- a/control/autoware_pid_longitudinal_controller/package.xml +++ b/control/autoware_pid_longitudinal_controller/package.xml @@ -2,7 +2,7 @@ autoware_pid_longitudinal_controller - 0.39.0 + 0.40.0 PID-based longitudinal controller Takamasa Horibe diff --git a/control/autoware_pure_pursuit/CHANGELOG.rst b/control/autoware_pure_pursuit/CHANGELOG.rst index df0b7df3a9e52..e0afa320a49a5 100644 --- a/control/autoware_pure_pursuit/CHANGELOG.rst +++ b/control/autoware_pure_pursuit/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_pure_pursuit ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* ci(pre-commit): update cpplint to 2.0.0 (`#9557 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_pure_pursuit): fix cppcheck unusedFunction (`#9276 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo, awf-autoware-bot[bot] + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_pure_pursuit/package.xml b/control/autoware_pure_pursuit/package.xml index 03c46dbc22bb6..06500ddb32af0 100644 --- a/control/autoware_pure_pursuit/package.xml +++ b/control/autoware_pure_pursuit/package.xml @@ -2,7 +2,7 @@ autoware_pure_pursuit - 0.39.0 + 0.40.0 The pure_pursuit package Takamasa Horibe Takayuki Murooka diff --git a/control/autoware_shift_decider/CHANGELOG.rst b/control/autoware_shift_decider/CHANGELOG.rst index 72257774b4763..2b5eda421e452 100644 --- a/control/autoware_shift_decider/CHANGELOG.rst +++ b/control/autoware_shift_decider/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_shift_decider ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/control/autoware_shift_decider/package.xml b/control/autoware_shift_decider/package.xml index 75b11dfcd8379..fb7811e094dc2 100644 --- a/control/autoware_shift_decider/package.xml +++ b/control/autoware_shift_decider/package.xml @@ -2,7 +2,7 @@ autoware_shift_decider - 0.39.0 + 0.40.0 The autoware_shift_decider package Takamasa Horibe Takayuki Murooka diff --git a/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst b/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst index 34bb120a2752c..d3dc4d5eb1aa8 100644 --- a/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst +++ b/control/autoware_smart_mpc_trajectory_follower/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_smart_mpc_trajectory_follower ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* fix(autoware_smart_mpc_trajectory_follower): fix clang-diagnostic-ignored-optimization-argument (`#9437 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/control/autoware_smart_mpc_trajectory_follower/package.xml b/control/autoware_smart_mpc_trajectory_follower/package.xml index fb70eb05d21e5..7260dee488c52 100644 --- a/control/autoware_smart_mpc_trajectory_follower/package.xml +++ b/control/autoware_smart_mpc_trajectory_follower/package.xml @@ -2,7 +2,7 @@ autoware_smart_mpc_trajectory_follower - 0.39.0 + 0.40.0 Nodes to follow a trajectory by generating control commands using smart mpc diff --git a/control/autoware_trajectory_follower_base/CHANGELOG.rst b/control/autoware_trajectory_follower_base/CHANGELOG.rst index 9182dabfe66a6..88ccd57905c89 100644 --- a/control/autoware_trajectory_follower_base/CHANGELOG.rst +++ b/control/autoware_trajectory_follower_base/CHANGELOG.rst @@ -2,6 +2,40 @@ Changelog for package autoware_trajectory_follower_base ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(trajectory_follower): publsih control horzion (`#8977 `_) + * feat(trajectory_follower): publsih control horzion + * fix typo + * rename functions and minor refactor + * add option to enable horizon pub + * add tests for horizon + * update docs + * rename to ~/debug/control_cmd_horizon + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/control/autoware_trajectory_follower_base/package.xml b/control/autoware_trajectory_follower_base/package.xml index 32bf2b1f1a809..e7b00e4b19cdc 100644 --- a/control/autoware_trajectory_follower_base/package.xml +++ b/control/autoware_trajectory_follower_base/package.xml @@ -2,7 +2,7 @@ autoware_trajectory_follower_base - 0.39.0 + 0.40.0 Library for generating lateral and longitudinal controls following a trajectory diff --git a/control/autoware_trajectory_follower_node/CHANGELOG.rst b/control/autoware_trajectory_follower_node/CHANGELOG.rst index fad7a121bb624..c77e252230bfb 100644 --- a/control/autoware_trajectory_follower_node/CHANGELOG.rst +++ b/control/autoware_trajectory_follower_node/CHANGELOG.rst @@ -2,6 +2,51 @@ Changelog for package autoware_trajectory_follower_node ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* refactor: correct spelling (`#9528 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(mpc_lateral_controller): suppress rclcpp_warning/error (`#9382 `_) + * feat(mpc_lateral_controller): suppress rclcpp_warning/error + * fix + * fix test + --------- +* fix(autoware_trajectory_follower_node): fix clang-diagnostic-format-security (`#9378 `_) +* refactor(fake_test_node): prefix package and namespace with autoware (`#9249 `_) +* feat(trajectory_follower): publsih control horzion (`#8977 `_) + * feat(trajectory_follower): publsih control horzion + * fix typo + * rename functions and minor refactor + * add option to enable horizon pub + * add tests for horizon + * update docs + * rename to ~/debug/control_cmd_horizon + --------- +* fix(control): missing dependency in control components (`#9073 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Takayuki Murooka, Yutaka Kondo, ぐるぐる + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_trajectory_follower_node/package.xml b/control/autoware_trajectory_follower_node/package.xml index e4000feef9474..aa65e340d20fe 100644 --- a/control/autoware_trajectory_follower_node/package.xml +++ b/control/autoware_trajectory_follower_node/package.xml @@ -2,7 +2,7 @@ autoware_trajectory_follower_node - 0.39.0 + 0.40.0 Nodes to follow a trajectory by generating control commands separated into lateral and longitudinal commands diff --git a/control/autoware_vehicle_cmd_gate/CHANGELOG.rst b/control/autoware_vehicle_cmd_gate/CHANGELOG.rst index ce6420fa69b76..38dae3279b1c8 100644 --- a/control/autoware_vehicle_cmd_gate/CHANGELOG.rst +++ b/control/autoware_vehicle_cmd_gate/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_vehicle_cmd_gate ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* fix(autoware_vehicle_cmd_gate): remove unused variable (`#9377 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(control): missing dependency in control components (`#9073 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(vehicle_cmd_gate): fix processing time measurement (`#9260 `_) +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Maxime CLEMENT, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo, ぐるぐる + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/autoware_vehicle_cmd_gate/package.xml b/control/autoware_vehicle_cmd_gate/package.xml index 3253f5a498933..c3697337e2256 100644 --- a/control/autoware_vehicle_cmd_gate/package.xml +++ b/control/autoware_vehicle_cmd_gate/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_cmd_gate - 0.39.0 + 0.40.0 The vehicle_cmd_gate package Takamasa Horibe Tomoya Kimura diff --git a/control/control_performance_analysis/CHANGELOG.rst b/control/control_performance_analysis/CHANGELOG.rst index f32fbe5cb0b1c..67b4f15ddde9f 100644 --- a/control/control_performance_analysis/CHANGELOG.rst +++ b/control/control_performance_analysis/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package control_performance_analysis ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* refactor(global_parameter_loader): prefix package and namespace with autoware (`#9303 `_) +* docs(control_performance_analysis): utilize mathjax syntax in readme (`#9552 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(control_performance_analysis): clang-diagnostic-pessimizing-move (`#9380 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/control/control_performance_analysis/package.xml b/control/control_performance_analysis/package.xml index 49b8f69570bb4..9c2ef69e0137b 100644 --- a/control/control_performance_analysis/package.xml +++ b/control/control_performance_analysis/package.xml @@ -2,7 +2,7 @@ control_performance_analysis - 0.39.0 + 0.40.0 Controller Performance Evaluation Berkay Karaman Taiki Tanaka diff --git a/control/predicted_path_checker/CHANGELOG.rst b/control/predicted_path_checker/CHANGELOG.rst index 15418d84cba3a..2cfe80aeada7b 100644 --- a/control/predicted_path_checker/CHANGELOG.rst +++ b/control/predicted_path_checker/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package predicted_path_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - control (`#9565 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/control/predicted_path_checker/package.xml b/control/predicted_path_checker/package.xml index f23828f8a586c..e2f9d17769e1a 100644 --- a/control/predicted_path_checker/package.xml +++ b/control/predicted_path_checker/package.xml @@ -2,7 +2,7 @@ predicted_path_checker - 0.39.0 + 0.40.0 The predicted_path_checker package Berkay Karaman diff --git a/evaluator/autoware_control_evaluator/CHANGELOG.rst b/evaluator/autoware_control_evaluator/CHANGELOG.rst index e67a53de4656a..88afa49d97cc3 100644 --- a/evaluator/autoware_control_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_control_evaluator/CHANGELOG.rst @@ -2,6 +2,74 @@ Changelog for package autoware_control_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - evaluator (`#9566 `_) +* fix(control_evaluator): correct goal_lateal_deviation (`#9532 `_) +* feat(control_evaluator, tier4_control_launch): add a trigger to choice whether to output metrics to log folder (`#9478 `_) + * refactor and add output_metrics. a bug existing when psim. + * refactored launch file. + * output description + * add parm to launch file. + * move output_metrics from param config to launch file. + * move output_metrics from config to launch.xml + * fix unit test bug. + * fix test bug again. + * Update evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp + --------- + Co-authored-by: Kosuke Takeuchi +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(control_evaluator): add processing time publisher (`#9339 `_) +* test(autoware_control_evaluator): add unit test for utils autoware_control_evaluator (`#9307 `_) + * update unit test of control_evaluator. + * manual pre-commit. + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kazunori-Nakajima, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/evaluator/autoware_control_evaluator/package.xml b/evaluator/autoware_control_evaluator/package.xml index 473f3bff7257e..a636a55bc5efd 100644 --- a/evaluator/autoware_control_evaluator/package.xml +++ b/evaluator/autoware_control_evaluator/package.xml @@ -2,7 +2,7 @@ autoware_control_evaluator - 0.39.0 + 0.40.0 ROS 2 node for evaluating control Daniel SANCHEZ takayuki MUROOKA diff --git a/evaluator/autoware_planning_evaluator/CHANGELOG.rst b/evaluator/autoware_planning_evaluator/CHANGELOG.rst index 9dc854ae8d623..77f544ae078fa 100644 --- a/evaluator/autoware_planning_evaluator/CHANGELOG.rst +++ b/evaluator/autoware_planning_evaluator/CHANGELOG.rst @@ -2,6 +2,77 @@ Changelog for package autoware_planning_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - evaluator (`#9566 `_) +* feat(planning_evaluator): add a trigger to choice whether to output metrics to log folder (`#9476 `_) + * tmp save + * planning_evaluator build ok, test it. + * add descriptions to output. + * pre-commit. + * add parm to launch file. + * move output_metrics from config to launch file. + * fix unit test bug. + --------- +* refactor(evaluators, autoware_universe_utils): rename Stat class to Accumulator and move it to autoware_universe_utils (`#9459 `_) + * add Accumulator class to autoware_universe_utils + * use Accumulator on all evaluators. + * pre-commit + * found and fixed a bug. add more tests. + * pre-commit + * Update common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* feat(planning_evaluator): add processing time pub (`#9334 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(evaluator): missing dependency in evaluator components (`#9074 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kazunori-Nakajima, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, ぐるぐる + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/evaluator/autoware_planning_evaluator/package.xml b/evaluator/autoware_planning_evaluator/package.xml index 09c8a17a8d791..4389b2e52f44d 100644 --- a/evaluator/autoware_planning_evaluator/package.xml +++ b/evaluator/autoware_planning_evaluator/package.xml @@ -2,7 +2,7 @@ autoware_planning_evaluator - 0.39.0 + 0.40.0 ROS 2 node for evaluating planners Maxime CLEMENT Kyoichi Sugahara diff --git a/evaluator/kinematic_evaluator/CHANGELOG.rst b/evaluator/kinematic_evaluator/CHANGELOG.rst index da5509f14143e..2283ea3b36a95 100644 --- a/evaluator/kinematic_evaluator/CHANGELOG.rst +++ b/evaluator/kinematic_evaluator/CHANGELOG.rst @@ -2,6 +2,43 @@ Changelog for package kinematic_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - evaluator (`#9566 `_) +* refactor(evaluators, autoware_universe_utils): rename Stat class to Accumulator and move it to autoware_universe_utils (`#9459 `_) + * add Accumulator class to autoware_universe_utils + * use Accumulator on all evaluators. + * pre-commit + * found and fixed a bug. add more tests. + * pre-commit + * Update common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(evaluator): missing dependency in evaluator components (`#9074 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, ぐるぐる + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/evaluator/kinematic_evaluator/package.xml b/evaluator/kinematic_evaluator/package.xml index ab01f15c3c154..fbd5df3f27765 100644 --- a/evaluator/kinematic_evaluator/package.xml +++ b/evaluator/kinematic_evaluator/package.xml @@ -1,7 +1,7 @@ kinematic_evaluator - 0.39.0 + 0.40.0 kinematic evaluator ROS 2 node Dominik Jargot diff --git a/evaluator/localization_evaluator/CHANGELOG.rst b/evaluator/localization_evaluator/CHANGELOG.rst index 7438643fe19a6..0c24579d3004d 100644 --- a/evaluator/localization_evaluator/CHANGELOG.rst +++ b/evaluator/localization_evaluator/CHANGELOG.rst @@ -2,6 +2,44 @@ Changelog for package localization_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - evaluator (`#9566 `_) +* chore(localization_evaluator): Add some maintainers (`#9503 `_) +* refactor(evaluators, autoware_universe_utils): rename Stat class to Accumulator and move it to autoware_universe_utils (`#9459 `_) + * add Accumulator class to autoware_universe_utils + * use Accumulator on all evaluators. + * pre-commit + * found and fixed a bug. add more tests. + * pre-commit + * Update common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(evaluator): missing dependency in evaluator components (`#9074 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), M. Fatih Cırıt, Motz, Ryohsuke Mitsudome, Yutaka Kondo, ぐるぐる + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/evaluator/localization_evaluator/package.xml b/evaluator/localization_evaluator/package.xml index a38871a1af6a2..7058064f17b72 100644 --- a/evaluator/localization_evaluator/package.xml +++ b/evaluator/localization_evaluator/package.xml @@ -1,7 +1,7 @@ localization_evaluator - 0.39.0 + 0.40.0 localization evaluator ROS 2 node Dominik Jargot diff --git a/evaluator/perception_online_evaluator/CHANGELOG.rst b/evaluator/perception_online_evaluator/CHANGELOG.rst index f3e999f66ee0e..c3ffd03cce3b1 100644 --- a/evaluator/perception_online_evaluator/CHANGELOG.rst +++ b/evaluator/perception_online_evaluator/CHANGELOG.rst @@ -2,6 +2,44 @@ Changelog for package perception_online_evaluator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - evaluator (`#9566 `_) +* refactor(perception_online_evaluator): use tier4_metric_msgs instead of diagnostic_msgs (`#9485 `_) +* refactor(evaluators, autoware_universe_utils): rename Stat class to Accumulator and move it to autoware_universe_utils (`#9459 `_) + * add Accumulator class to autoware_universe_utils + * use Accumulator on all evaluators. + * pre-commit + * found and fixed a bug. add more tests. + * pre-commit + * Update common/autoware_universe_utils/include/autoware/universe_utils/math/accumulator.hpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(evaluator): missing dependency in evaluator components (`#9074 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), Kotaro Uetake, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, ぐるぐる + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/evaluator/perception_online_evaluator/package.xml b/evaluator/perception_online_evaluator/package.xml index bebc46457807e..94575a0adbb4c 100644 --- a/evaluator/perception_online_evaluator/package.xml +++ b/evaluator/perception_online_evaluator/package.xml @@ -2,7 +2,7 @@ perception_online_evaluator - 0.39.0 + 0.40.0 ROS 2 node for evaluating perception Fumiya Watanabe Kosuke Takeuchi diff --git a/evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst b/evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst new file mode 100644 index 0000000000000..7b583a3da7959 --- /dev/null +++ b/evaluator/scenario_simulator_v2_adapter/CHANGELOG.rst @@ -0,0 +1,498 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package scenario_simulator_v2_adapter +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix(cpplint): include what you use - evaluator (`#9566 `_) +* fix(scenario_simulator_v2_adapter): remove invalid CHANGELOG.rst file (`#9501 `_) +* 0.39.0 +* fix version +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix(cpplint): include what you use - evaluator (`#9566 `_) +* fix(scenario_simulator_v2_adapter): remove invalid CHANGELOG.rst file (`#9501 `_) +* 0.39.0 +* fix version +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + +0.39.0 (2024-11-25) +------------------- +* chore(package.xml): bump version to 0.39.0 (`#9435 `_) + * chore: update CODEOWNERS (`#9203 `_) + Co-authored-by: github-actions + * refactor(time_utils): prefix package and namespace with autoware (`#9173 `_) + * refactor(time_utils): prefix package and namespace with autoware + * refactor(time_utils): prefix package and namespace with autoware + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * feat(rtc_interface): add requested field (`#9202 `_) + * add requested feature + * Update planning/autoware_rtc_interface/test/test_rtc_interface.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + * fix(mpc_lateral_controller): correctly resample the MPC trajectory yaws (`#9199 `_) + * fix(bpp): prevent accessing nullopt (`#9204 `_) + fix(bpp): calcDistanceToRedTrafficLight null + * refactor(autoware_map_based_prediction): split pedestrian and bicycle predictor (`#9201 `_) + * refactor: grouping functions + * refactor: grouping parameters + * refactor: rename member road_users_history to road_users_history\_ + * refactor: separate util functions + * refactor: Add predictor_vru.cpp and utils.cpp to map_based_prediction_node + * refactor: Add explicit template instantiation for removeOldObjectsHistory function + * refactor: Add tf2_geometry_msgs to data_structure + * refactor: Remove unused variables and functions in map_based_prediction_node.cpp + * Update perception/autoware_map_based_prediction/include/map_based_prediction/predictor_vru.hpp + * Apply suggestions from code review + * style(pre-commit): autofix + --------- + Co-authored-by: Mamoru Sobue + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (`#8912 `_) + * Moved ndt_omp into ndt_scan_matcher + * Added Copyright + * style(pre-commit): autofix + * Fixed include + * Fixed cast style + * Fixed include + * Fixed honorific title + * Fixed honorific title + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed hierarchy + * Fixed NVTP to NVTL + * Added cspell:ignore + * Fixed miss spell + * style(pre-commit): autofix + * Fixed include + * Renamed applyFilter + * Moved ***_impl.hpp from include/ to src/ + * style(pre-commit): autofix + * Fixed variable scope + * Fixed to pass by reference + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * feat(autoware_test_utils): add traffic light msgs parser (`#9177 `_) + * fix(rtc_interface): update requested field for every cooperateStatus state (`#9211 `_) + * fix rtc_interface + * fix test condition + --------- + * feat(static_obstacle_avoidance): operator request for ambiguous vehicle (`#9205 `_) + * add operator request feature + * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + * feat(collision_detector): use polling subscriber (`#9213 `_) + use polling subscriber + * fix(diagnostic_graph_utils): reset graph when new one is received (`#9208 `_) + fix(diagnostic_graph_utils): reset graph when new one is reveived + * fix(autoware_ndt_scan_matcher): reduce initial_pose_estimation.particles_num from 200 to 100 on tests (`#9218 `_) + Reduced initial_pose_estimation.particles_num from 200 to 100 on tests + * feat(control_launch): add collision detector in launch (`#9214 `_) + add collision detector in launch + * chore(obstacle_cruise_planner): add function tests for a utils function (`#9206 `_) + * add utils test + --------- + * fix(bvp): remove expired module safely (`#9212 `_) + * fix(bvp): remove expired module safely + * fix: remove module id set + * fix: use itr to erase expired module + * fix: remove unused function + --------- + * test(bpp_common): add unit test for safety check (`#9223 `_) + * add test for object collision + * add test for more functions + * add docstring + * fix lane change + --------- + * fix(autoware_behavior_path_goal_planner_module): fix cppcheck unreadVariable (`#9192 `_) + * fix(autoware_image_projection_based_fusion): fix bugprone-misplaced-widening-cast (`#9229 `_) + * fix: bugprone-misplaced-widening-cast + * fix: clang-format + --------- + * fix(autoware_euclidean_cluster): fix bugprone-misplaced-widening-cast (`#9227 `_) + fix: bugprone-misplaced-widening-cast + * fix(autoware_image_projection_based_fusion): fix bugprone-misplaced-widening-cast (`#9226 `_) + * fix: bugprone-misplaced-widening-cast + * fix: clang-format + --------- + * fix(autoware_compare_map_segmentation): fix cppcheck constVariableReference (`#9196 `_) + * refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) + * fix(autoware_behavior_velocity_no_stopping_area_module): fix cppcheck knownConditionTrueFalse (`#9189 `_) + * fix(autoware_freespace_planning_algorithms): fix bugprone-unused-raii (`#9230 `_) + fix: bugprone-unused-raii + * refactor(map_based_prediction): divide objectsCallback (`#9219 `_) + * refactor(map_based_prediction): move member functions to utils (`#9225 `_) + * test(crosswalk): add unit test (`#9228 `_) + * fix(autoware_probabilistic_occupancy_grid_map): fix bugprone-incorrect-roundings (`#9221 `_) + fix: bugprone-incorrect-roundings + * refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) + * fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback (`#9234 `_) + * feat(autoware_motion_utils): add new trajectory class (`#8693 `_) + * feat(autoware_motion_utils): add interpolator + * use int32_t instead of int + * use int32_t instead of int + * use int32_t instead of int + * add const as much as possible and use `at()` in `vector` + * fix directory name + * refactor code and add example + * update + * remove unused include + * refactor code + * add clone function + * fix stairstep + * make constructor to public + * feat(autoware_motion_utils): add trajectory class + * Update CMakeLists.txt + * fix + * fix package.xml + * update crop + * revert crtp change + * update package.xml + * updating... + * update + * solve build problem + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * fix(autoware_image_projection_based_fusion): make optional to consider lens distortion in the point projection (`#9233 `_) + chore: add point_project_to_unrectified_image parameter to fusion_common.param.yaml + * feat(autoware_test_utils): add general topic dumper (`#9207 `_) + * fix(autoware_ekf_localizer): remove `timer_tf\_` (`#9244 `_) + Removed timer_tf\_ + * fix(autoware_rtc_interface): fix dependency (`#9237 `_) + * fix(autonomous_emergency_braking): solve issue with arc length (`#9247 `_) + * solve issue with arc length + * fix problem with points one vehicle apart from path + --------- + * fix(autoware_lidar_apollo_instance_segmentation): fix cppcheck suspiciousFloatingPointCast (`#9195 `_) + * fix(autoware_behavior_path_sampling_planner_module): fix cppcheck unusedVariable (`#9190 `_) + * refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) + * chore(autoware_geography_utils): update maintainers (`#9246 `_) + * update maintainers + * add author + --------- + * fix(lane_change): enable cancel when ego in turn direction lane (`#9124 `_) + * RT0-33893 add checks from prev intersection + * fix shadow variable + * fix logic + * update readme + * refactor get_ego_footprint + --------- + * fix(out_of_lane): correct calculations of the stop pose (`#9209 `_) + * fix(autoware_pointcloud_preprocessor): launch file load parameter from yaml (`#8129 `_) + * feat: fix launch file + * chore: fix spell error + * chore: fix parameters file name + * chore: remove filter base + --------- + * fix: missing dependency in common components (`#9072 `_) + * feat(autoware_trajectory): move trajectory_container from autoware_motion_utils to a new package (`#9253 `_) + * create trajectory container package + * update + * update + * style(pre-commit): autofix + * update codeowner + * update + * fix cmake + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * fix(autoware_pointcloud_preprocessor): fix the wrong naming of crop box parameter file (`#9258 `_) + fix: fix the wrong file name + * fix(dummy_diag_publisher): not use diagnostic_updater and param callback (`#9257 `_) + * fix(dummy_diag_publisher): not use diagnostic_updater and param callback for v0.29.0 (`#1414 `_) + fix(dummy_diag_publisher): not use diagnostic_updater and param callback + Co-authored-by: h-ohta + * fix: resolve build error of dummy diag publisher (`#1415 `_) + fix merge conflict + --------- + Co-authored-by: Shohei Sakai + Co-authored-by: h-ohta + * test(behavior_path_planner_common): add unit test for path shifter (`#9239 `_) + * add unit test for path shifter + * fix unnecessary modification + * fix spelling mistake + * add docstring + --------- + * feat(system_monitor): support loopback network interface (`#9067 `_) + * feat(system_monitor): support loopback network interface + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * feat(autoware_trajectory): change interface of InterpolatedArray (`#9264 `_) + change interface of InterpolateArray + * feat(system_monitor): add on/off config for network traffic monitor (`#9069 `_) + * feat(system_monitor): add config for network traffic monitor + * fix: change function name from stop to skip + --------- + * feat(detection_area)!: add retruction feature (`#9255 `_) + * fix(vehicle_cmd_gate): fix processing time measurement (`#9260 `_) + * fix(bvp): use polling subscriber (`#9242 `_) + * fix(bvp): use polling subscriber + * fix: use newest policy + --------- + * refactor(lane_change): remove std::optional from lanes polygon (`#9267 `_) + * fix(bpp): prevent accessing nullopt (`#9269 `_) + * refactor(lane_change): revert "remove std::optional from lanes polygon" (`#9272 `_) + Revert "refactor(lane_change): remove std::optional from lanes polygon (`#9267 `_)" + This reverts commit 0c70ea8793985c6aae90f851eeffdd2561fe04b3. + * feat(goal_planner): sort candidate path only when num to avoid is different (`#9271 `_) + * fix(/autoware_freespace_planning_algorithms): fix cppcheck unusedFunction (`#9274 `_) + * fix(autoware_behavior_path_start_planner_module): fix cppcheck unreadVariable (`#9277 `_) + * fix(autoware_ndt_scan_matcher): fix cppcheck unusedFunction (`#9275 `_) + * fix(autoware_pure_pursuit): fix cppcheck unusedFunction (`#9276 `_) + * fix(lane_change): correct computation of maximum lane changing length threshold (`#9279 `_) + fix computation of maximum lane changing length threshold + * feat(aeb): set global param to override autoware state check (`#9263 `_) + * set global param to override autoware state check + * change variable to be more general + * add comment + * move param to control component launch + * change param name to be more straightforward + --------- + * fix(autoware_default_adapi): change subscribing steering factor topic name for obstacle avoidance and lane changes (`#9273 `_) + feat(planning): add new steering factor topics for obstacle avoidance and lane changes + * chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- + * fix(lane_change): extending lane change path for multiple lane change (RT1-8427) (`#9268 `_) + * RT1-8427 extending lc path for multiple lc + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * fix(autoware_utils): address self-intersecting polygons in random_concave_generator and handle empty inners() during triangulation (`#8995 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * fix(behavior_path_planner_common): use boost intersects instead of overlaps (`#9289 `_) + * fix(behavior_path_planner_common): use boost intersects instead of overlaps + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp + Co-authored-by: Go Sakayori + --------- + Co-authored-by: Go Sakayori + * ci(.github): update image tags (`#9286 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- + * fix(autoware_mpc_lateral_controller): fix bugprone-misplaced-widening-cast (`#9224 `_) + * fix: bugprone-misplaced-widening-cast + * fix: consider negative values + --------- + * fix(autoware_detected_object_validation): fix clang-diagnostic-error (`#9215 `_) + fix: clang-c-error + * fix(autoware_detected_object_validation): fix bugprone-incorrect-roundings (`#9220 `_) + fix: bugprone-incorrect-roundings + * feat(autoware_test_utils): use sample_vehicle/sample_sensor_kit (`#9290 `_) + * refactor(lane_change): remove std::optional from lanes polygon (`#9288 `_) + * feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- + * feat(diagnostic_graph_aggregator): implement diagnostic graph dump functionality (`#9261 `_) + * chore(tvm_utility): remove tvm_utility package as it is no longer used (`#9291 `_) + * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) + * perf(autoware_ndt_scan_matcher): remove evecs\_, evals\_ of Leaf for memory efficiency (`#9281 `_) + * fix(lane_change): correct computation of maximum lane changing length threshold (`#9279 `_) + fix computation of maximum lane changing length threshold + * perf: remove evecs, evals from Leaf + * perf: remove evecs, evals from Leaf + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * test(costmap_generator): unit test implementation for costmap generator (`#9149 `_) + * modify costmap generator directory structure + * rename class CostmapGenerator to CostmapGeneratorNode + * unit test for object_map_utils + * catch error from lookupTransform + * use polling subscriber in costmap generator node + * add test for costmap generator node + * add test for isActive() + * revert unnecessary changes + * remove commented out line + * minor fix + * Update planning/autoware_costmap_generator/src/costmap_generator.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi + * fix(control): missing dependency in control components (`#9073 `_) + * test(autoware_control_evaluator): add unit test for utils autoware_control_evaluator (`#9307 `_) + * update unit test of control_evaluator. + * manual pre-commit. + --------- + * fix(collision_detector): skip process when odometry is not published (`#9308 `_) + * subscribe odometry + * fix precommit + * remove unnecessary log info + --------- + * feat(goal_planner): safety check with only parking path (`#9293 `_) + * refactor(goal_planner): remove reference_goal_pose getter/setter (`#9270 `_) + * feat(start_planner, lane_departure_checker): speed up by updating polygons (`#9309 `_) + speed up by updating polygons + * fix(autoware_trajectory): fix bug of autoware_trajectory (`#9314 `_) + * feat(autoware_trajectory): change default value of min_points (`#9315 `_) + * chore(codecov): update maintained packages (`#9316 `_) + * doc: fix links to design documents (`#9301 `_) + * fix(costmap_generator): use vehicle frame for lidar height thresholds (`#9311 `_) + * fix(tier4_dummy_object_rviz_plugin): fix missing dependency (`#9306 `_) + * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) + * add changelog + * update changelog + * fix version + * 0.39.0 + * refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- + * update version + --------- + Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]@users.noreply.github.com> + Co-authored-by: github-actions + Co-authored-by: Esteve Fernandez <33620+esteve@users.noreply.github.com> + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Go Sakayori + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> + Co-authored-by: Taekjin LEE + Co-authored-by: Mamoru Sobue + Co-authored-by: SakodaShintaro + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> + Co-authored-by: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> + Co-authored-by: Ryuta Kambe + Co-authored-by: kobayu858 <129580202+kobayu858@users.noreply.github.com> + Co-authored-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> + Co-authored-by: danielsanchezaran + Co-authored-by: Yamato Ando + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + Co-authored-by: Yi-Hsiang Fang (Vivid) <146902905+vividf@users.noreply.github.com> + Co-authored-by: ぐるぐる + Co-authored-by: Shohei Sakai + Co-authored-by: h-ohta + Co-authored-by: iwatake + Co-authored-by: Kosuke Takeuchi + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + Co-authored-by: Kyoichi Sugahara + Co-authored-by: Giovanni Muhammad Raditya + Co-authored-by: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> + Co-authored-by: Kem (TiankuiXian) <1041084556@qq.com> + Co-authored-by: Kento Osa <38522559+taisa1@users.noreply.github.com> + Co-authored-by: Masaki Baba +* Contributors: Yutaka Kondo + +0.38.0 (2024-11-11) +------------------- diff --git a/evaluator/scenario_simulator_v2_adapter/package.xml b/evaluator/scenario_simulator_v2_adapter/package.xml index 45c4f91c0eb83..3922bc84d78d5 100644 --- a/evaluator/scenario_simulator_v2_adapter/package.xml +++ b/evaluator/scenario_simulator_v2_adapter/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2_adapter - 0.39.0 + 0.40.0 Node for converting autoware's messages into UserDefinedValue messages Kyoichi Sugahara Maxime CLEMENT diff --git a/launch/tier4_autoware_api_launch/CHANGELOG.rst b/launch/tier4_autoware_api_launch/CHANGELOG.rst index 38825528d8c39..5892c238a3bd6 100644 --- a/launch/tier4_autoware_api_launch/CHANGELOG.rst +++ b/launch/tier4_autoware_api_launch/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_autoware_api_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/launch/tier4_autoware_api_launch/package.xml b/launch/tier4_autoware_api_launch/package.xml index 4b52acbc8d804..45df577f28f29 100644 --- a/launch/tier4_autoware_api_launch/package.xml +++ b/launch/tier4_autoware_api_launch/package.xml @@ -2,7 +2,7 @@ tier4_autoware_api_launch - 0.39.0 + 0.40.0 The tier4_autoware_api_launch package Takagi, Isamu Ryohsuke Mitsudome diff --git a/launch/tier4_control_launch/CHANGELOG.rst b/launch/tier4_control_launch/CHANGELOG.rst index cbe41dcd85828..3f94ac4f2b2e0 100644 --- a/launch/tier4_control_launch/CHANGELOG.rst +++ b/launch/tier4_control_launch/CHANGELOG.rst @@ -2,6 +2,77 @@ Changelog for package tier4_control_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix: autoware_glog_compontnt (`#9586 `_) + Fixed autoware_glog_compontnt +* refactor(glog_component): prefix package and namespace with autoware (`#9302 `_) + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> +* feat(control_evaluator, tier4_control_launch): add a trigger to choice whether to output metrics to log folder (`#9478 `_) + * refactor and add output_metrics. a bug existing when psim. + * refactored launch file. + * output description + * add parm to launch file. + * move output_metrics from param config to launch file. + * move output_metrics from config to launch.xml + * fix unit test bug. + * fix test bug again. + * Update evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp + --------- + Co-authored-by: Kosuke Takeuchi +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_control_launch): use preset.yaml to control which modules to launch for control modules (`#9351 `_) + * update contro.launch for preset.xml + * update options. + * fix bug. + * rename to enable\_* + * check group. + * space. + * reduce num of load_composable_node. + * tmp save. + * tmp save. + * splite control modules' launch. + * final version + * remove on/off option for shift decider, vehicle cmd gate, and operation mode transition manager + * pre-commit + --------- +* fix(collision_detector): skip process when odometry is not published (`#9308 `_) + * subscribe odometry + * fix precommit + * remove unnecessary log info + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(aeb): set global param to override autoware state check (`#9263 `_) + * set global param to override autoware state check + * change variable to be more general + * add comment + * move param to control component launch + * change param name to be more straightforward + --------- +* feat(control_launch): add collision detector in launch (`#9214 `_) + add collision detector in launch +* Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, Kem (TiankuiXian), Ryohsuke Mitsudome, SakodaShintaro, Yutaka Kondo, danielsanchezaran + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/launch/tier4_control_launch/package.xml b/launch/tier4_control_launch/package.xml index 09eb3302c7811..d9a2f9883cbce 100644 --- a/launch/tier4_control_launch/package.xml +++ b/launch/tier4_control_launch/package.xml @@ -2,7 +2,7 @@ tier4_control_launch - 0.39.0 + 0.40.0 The tier4_control_launch package Takamasa Horibe Takayuki Murooka diff --git a/launch/tier4_localization_launch/CHANGELOG.rst b/launch/tier4_localization_launch/CHANGELOG.rst index 21cf37981a40a..991f04240d04d 100644 --- a/launch/tier4_localization_launch/CHANGELOG.rst +++ b/launch/tier4_localization_launch/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_localization_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 66d2a3277f505..55c9c59a2b000 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -2,7 +2,7 @@ tier4_localization_launch - 0.39.0 + 0.40.0 The tier4_localization_launch package Yamato Ando Kento Yabuuchi diff --git a/launch/tier4_map_launch/CHANGELOG.rst b/launch/tier4_map_launch/CHANGELOG.rst index 11f8aeb97cda3..5ba95030bf15b 100644 --- a/launch/tier4_map_launch/CHANGELOG.rst +++ b/launch/tier4_map_launch/CHANGELOG.rst @@ -2,6 +2,50 @@ Changelog for package tier4_map_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Masaki Baba, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml index 91874321b5db0..ba512960af1b2 100644 --- a/launch/tier4_map_launch/package.xml +++ b/launch/tier4_map_launch/package.xml @@ -2,7 +2,7 @@ tier4_map_launch - 0.39.0 + 0.40.0 The tier4_map_launch package Ryu Yamamoto Kento Yabuuchi diff --git a/launch/tier4_perception_launch/CHANGELOG.rst b/launch/tier4_perception_launch/CHANGELOG.rst index 412665dab796f..b8ac734476a36 100644 --- a/launch/tier4_perception_launch/CHANGELOG.rst +++ b/launch/tier4_perception_launch/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_perception_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/launch/tier4_perception_launch/package.xml b/launch/tier4_perception_launch/package.xml index 7b705d4b74f78..613223fa960bd 100644 --- a/launch/tier4_perception_launch/package.xml +++ b/launch/tier4_perception_launch/package.xml @@ -2,7 +2,7 @@ tier4_perception_launch - 0.39.0 + 0.40.0 The tier4_perception_launch package Yukihiro Saito Shunsuke Miura diff --git a/launch/tier4_planning_launch/CHANGELOG.rst b/launch/tier4_planning_launch/CHANGELOG.rst index 2641162594a74..efa4a02803c46 100644 --- a/launch/tier4_planning_launch/CHANGELOG.rst +++ b/launch/tier4_planning_launch/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package tier4_planning_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix: autoware_glog_compontnt (`#9586 `_) + Fixed autoware_glog_compontnt +* refactor(glog_component): prefix package and namespace with autoware (`#9302 `_) + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> +* refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files (`#9470 `_) + * refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files + * Update planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> + * fix + --------- + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, SakodaShintaro, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 286e09a2f17ed..0a6e9d7fce13a 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -2,7 +2,7 @@ tier4_planning_launch - 0.39.0 + 0.40.0 The tier4_planning_launch package diff --git a/launch/tier4_sensing_launch/CHANGELOG.rst b/launch/tier4_sensing_launch/CHANGELOG.rst index 7e1b9756effdd..7e6e12e53a08c 100644 --- a/launch/tier4_sensing_launch/CHANGELOG.rst +++ b/launch/tier4_sensing_launch/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_sensing_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/launch/tier4_sensing_launch/package.xml b/launch/tier4_sensing_launch/package.xml index 12194a163e0f1..6e7553ac9f8f0 100644 --- a/launch/tier4_sensing_launch/package.xml +++ b/launch/tier4_sensing_launch/package.xml @@ -2,7 +2,7 @@ tier4_sensing_launch - 0.39.0 + 0.40.0 The tier4_sensing_launch package Yukihiro Saito Apache License 2.0 diff --git a/launch/tier4_simulator_launch/CHANGELOG.rst b/launch/tier4_simulator_launch/CHANGELOG.rst index 46aa2059dea76..569da150b16ae 100644 --- a/launch/tier4_simulator_launch/CHANGELOG.rst +++ b/launch/tier4_simulator_launch/CHANGELOG.rst @@ -2,6 +2,60 @@ Changelog for package tier4_simulator_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* refactor(vehicle_velocity_converter)!: prefix package and namespace with autoware (`#8967 `_) + * add autoware prefix + * fix conflict + --------- + Co-authored-by: Yamato Ando +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), Masaki Baba, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/launch/tier4_simulator_launch/package.xml b/launch/tier4_simulator_launch/package.xml index b61954dcc297d..19bc81b056b60 100644 --- a/launch/tier4_simulator_launch/package.xml +++ b/launch/tier4_simulator_launch/package.xml @@ -2,7 +2,7 @@ tier4_simulator_launch - 0.39.0 + 0.40.0 The tier4_simulator_launch package Keisuke Shima Takayuki Murooka diff --git a/launch/tier4_system_launch/CHANGELOG.rst b/launch/tier4_system_launch/CHANGELOG.rst index 26f1031652d54..9ffb34c4599a9 100644 --- a/launch/tier4_system_launch/CHANGELOG.rst +++ b/launch/tier4_system_launch/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_system_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/launch/tier4_system_launch/package.xml b/launch/tier4_system_launch/package.xml index 92bee6d1d3e86..9f5678b937dbc 100644 --- a/launch/tier4_system_launch/package.xml +++ b/launch/tier4_system_launch/package.xml @@ -2,7 +2,7 @@ tier4_system_launch - 0.39.0 + 0.40.0 The tier4_system_launch package Fumihito Ito TetsuKawa diff --git a/launch/tier4_vehicle_launch/CHANGELOG.rst b/launch/tier4_vehicle_launch/CHANGELOG.rst index 4823ed84f46f6..1b5a1271e9fe3 100644 --- a/launch/tier4_vehicle_launch/CHANGELOG.rst +++ b/launch/tier4_vehicle_launch/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package tier4_vehicle_launch ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/launch/tier4_vehicle_launch/package.xml b/launch/tier4_vehicle_launch/package.xml index ab3e7483c8593..583bbf325db05 100644 --- a/launch/tier4_vehicle_launch/package.xml +++ b/launch/tier4_vehicle_launch/package.xml @@ -2,7 +2,7 @@ tier4_vehicle_launch - 0.39.0 + 0.40.0 The tier4_vehicle_launch package Yukihiro Saito Apache License 2.0 diff --git a/localization/autoware_ekf_localizer/CHANGELOG.rst b/localization/autoware_ekf_localizer/CHANGELOG.rst index 369a731d87ee6..b8e74c530e059 100644 --- a/localization/autoware_ekf_localizer/CHANGELOG.rst +++ b/localization/autoware_ekf_localizer/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_ekf_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* fix(autoware_ekf_localizer): publish `processing_time_ms` (`#9443 `_) + Fixed to publish processing_time_ms +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_ekf_localizer): remove `timer_tf\_` (`#9244 `_) + Removed timer_tf\_ +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, SakodaShintaro, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/localization/autoware_ekf_localizer/package.xml b/localization/autoware_ekf_localizer/package.xml index d93b4eb1ff016..8dc3cc9844c50 100644 --- a/localization/autoware_ekf_localizer/package.xml +++ b/localization/autoware_ekf_localizer/package.xml @@ -2,7 +2,7 @@ autoware_ekf_localizer - 0.39.0 + 0.40.0 The autoware_ekf_localizer package Takamasa Horibe Yamato Ando diff --git a/localization/autoware_geo_pose_projector/CHANGELOG.rst b/localization/autoware_geo_pose_projector/CHANGELOG.rst index 717118a5c1692..1b45974da9cc2 100644 --- a/localization/autoware_geo_pose_projector/CHANGELOG.rst +++ b/localization/autoware_geo_pose_projector/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_geo_pose_projector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/localization/autoware_geo_pose_projector/package.xml b/localization/autoware_geo_pose_projector/package.xml index 4fecd89630e01..6dda1d6418406 100644 --- a/localization/autoware_geo_pose_projector/package.xml +++ b/localization/autoware_geo_pose_projector/package.xml @@ -2,7 +2,7 @@ autoware_geo_pose_projector - 0.39.0 + 0.40.0 The autoware_geo_pose_projector package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_gyro_odometer/CHANGELOG.rst b/localization/autoware_gyro_odometer/CHANGELOG.rst index 950fd01b2ce6f..529fe48f7b459 100644 --- a/localization/autoware_gyro_odometer/CHANGELOG.rst +++ b/localization/autoware_gyro_odometer/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_gyro_odometer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_gyro_odometer/package.xml b/localization/autoware_gyro_odometer/package.xml index b546312ef729e..87474c0b13c0f 100644 --- a/localization/autoware_gyro_odometer/package.xml +++ b/localization/autoware_gyro_odometer/package.xml @@ -2,7 +2,7 @@ autoware_gyro_odometer - 0.39.0 + 0.40.0 The autoware_gyro_odometer package as a ROS 2 node Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst index e8cc6d9f2796e..36d7431a499ff 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_ar_tag_based_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml index c0ee5cf973001..4aab7e0b5cdaf 100644 --- a/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_ar_tag_based_localizer/package.xml @@ -2,7 +2,7 @@ autoware_ar_tag_based_localizer - 0.39.0 + 0.40.0 The autoware_ar_tag_based_localizer package Shintaro Sakoda Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst index e50f441c27ca5..f6d4cf6766e84 100644 --- a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_landmark_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml index 357fc2b9eb32c..c33b8a751ce7f 100644 --- a/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_landmark_manager/package.xml @@ -2,7 +2,7 @@ autoware_landmark_manager - 0.39.0 + 0.40.0 The autoware_landmark_manager package Shintaro Sakoda Masahiro Sakamoto diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst index 374bdd1f09901..a7edd5b7d2a69 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_lidar_marker_localizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml index 72bded6b2b416..c365f7ef040dc 100755 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/package.xml @@ -2,7 +2,7 @@ autoware_lidar_marker_localizer - 0.39.0 + 0.40.0 The autoware_lidar_marker_localizer package Yamato Ando Shintaro Sakoda diff --git a/localization/autoware_localization_error_monitor/CHANGELOG.rst b/localization/autoware_localization_error_monitor/CHANGELOG.rst index ba263d0f8cb42..e9583916e2e8f 100644 --- a/localization/autoware_localization_error_monitor/CHANGELOG.rst +++ b/localization/autoware_localization_error_monitor/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_localization_error_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_localization_error_monitor/package.xml b/localization/autoware_localization_error_monitor/package.xml index 937d4e71bc717..f7f9e635e85d6 100644 --- a/localization/autoware_localization_error_monitor/package.xml +++ b/localization/autoware_localization_error_monitor/package.xml @@ -2,7 +2,7 @@ autoware_localization_error_monitor - 0.39.0 + 0.40.0 ros node for monitoring localization error Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_localization_util/CHANGELOG.rst b/localization/autoware_localization_util/CHANGELOG.rst index d029d05144595..be40e3ee8560e 100644 --- a/localization/autoware_localization_util/CHANGELOG.rst +++ b/localization/autoware_localization_util/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_localization_util ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_localization_util/package.xml b/localization/autoware_localization_util/package.xml index ea22ffe59ce64..89ad7c24840dd 100644 --- a/localization/autoware_localization_util/package.xml +++ b/localization/autoware_localization_util/package.xml @@ -2,7 +2,7 @@ autoware_localization_util - 0.39.0 + 0.40.0 The autoware_localization_util package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_ndt_scan_matcher/CHANGELOG.rst b/localization/autoware_ndt_scan_matcher/CHANGELOG.rst index 096804e155328..8040641aa2cef 100644 --- a/localization/autoware_ndt_scan_matcher/CHANGELOG.rst +++ b/localization/autoware_ndt_scan_matcher/CHANGELOG.rst @@ -2,6 +2,71 @@ Changelog for package autoware_ndt_scan_matcher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_ndt_scan_matcher): remove unsed functions (`#9387 `_) +* perf(autoware_ndt_scan_matcher): remove evecs\_, evals\_ of Leaf for memory efficiency (`#9281 `_) + * fix(lane_change): correct computation of maximum lane changing length threshold (`#9279 `_) + fix computation of maximum lane changing length threshold + * perf: remove evecs, evals from Leaf + * perf: remove evecs, evals from Leaf + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_ndt_scan_matcher): fix cppcheck unusedFunction (`#9275 `_) +* fix(autoware_ndt_scan_matcher): reduce initial_pose_estimation.particles_num from 200 to 100 on tests (`#9218 `_) + Reduced initial_pose_estimation.particles_num from 200 to 100 on tests +* refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (`#8912 `_) + * Moved ndt_omp into ndt_scan_matcher + * Added Copyright + * style(pre-commit): autofix + * Fixed include + * Fixed cast style + * Fixed include + * Fixed honorific title + * Fixed honorific title + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed hierarchy + * Fixed NVTP to NVTL + * Added cspell:ignore + * Fixed miss spell + * style(pre-commit): autofix + * Fixed include + * Renamed applyFilter + * Moved ***_impl.hpp from include/ to src/ + * style(pre-commit): autofix + * Fixed variable scope + * Fixed to pass by reference + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kento Osa, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, SakodaShintaro, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/localization/autoware_ndt_scan_matcher/package.xml b/localization/autoware_ndt_scan_matcher/package.xml index 96c73f248a595..f2047418310aa 100644 --- a/localization/autoware_ndt_scan_matcher/package.xml +++ b/localization/autoware_ndt_scan_matcher/package.xml @@ -2,7 +2,7 @@ autoware_ndt_scan_matcher - 0.39.0 + 0.40.0 The autoware_ndt_scan_matcher package Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_pose2twist/CHANGELOG.rst b/localization/autoware_pose2twist/CHANGELOG.rst index dcabfddfd2256..3f17982f52f31 100644 --- a/localization/autoware_pose2twist/CHANGELOG.rst +++ b/localization/autoware_pose2twist/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_pose2twist ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_pose2twist/package.xml b/localization/autoware_pose2twist/package.xml index 9e7ec378c8570..3fd16856ef6af 100644 --- a/localization/autoware_pose2twist/package.xml +++ b/localization/autoware_pose2twist/package.xml @@ -2,7 +2,7 @@ autoware_pose2twist - 0.39.0 + 0.40.0 The autoware_pose2twist package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_pose_covariance_modifier/CHANGELOG.rst b/localization/autoware_pose_covariance_modifier/CHANGELOG.rst index b3c5fdc70f36a..6fc366d3d01d5 100644 --- a/localization/autoware_pose_covariance_modifier/CHANGELOG.rst +++ b/localization/autoware_pose_covariance_modifier/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_pose_covariance_modifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_pose_covariance_modifier/package.xml b/localization/autoware_pose_covariance_modifier/package.xml index 2490fdc43dc0a..7825bd59b78f9 100644 --- a/localization/autoware_pose_covariance_modifier/package.xml +++ b/localization/autoware_pose_covariance_modifier/package.xml @@ -2,7 +2,7 @@ autoware_pose_covariance_modifier - 0.39.0 + 0.40.0 Add a description. Melike Tanrikulu diff --git a/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst b/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst index 423a73677c311..381b77546e008 100644 --- a/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst +++ b/localization/autoware_pose_estimator_arbiter/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_pose_estimator_arbiter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_pose_estimator_arbiter): add missing include (`#9376 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_pose_estimator_arbiter/package.xml b/localization/autoware_pose_estimator_arbiter/package.xml index cf30e8fcb5ef6..c6a47ae5755b3 100644 --- a/localization/autoware_pose_estimator_arbiter/package.xml +++ b/localization/autoware_pose_estimator_arbiter/package.xml @@ -2,7 +2,7 @@ autoware_pose_estimator_arbiter - 0.39.0 + 0.40.0 The arbiter of multiple pose estimators Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_pose_initializer/CHANGELOG.rst b/localization/autoware_pose_initializer/CHANGELOG.rst index ca509039af804..45473a9444270 100644 --- a/localization/autoware_pose_initializer/CHANGELOG.rst +++ b/localization/autoware_pose_initializer/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/localization/autoware_pose_initializer/package.xml b/localization/autoware_pose_initializer/package.xml index e23a319e2ac2b..eeeb46a8db3e5 100644 --- a/localization/autoware_pose_initializer/package.xml +++ b/localization/autoware_pose_initializer/package.xml @@ -2,7 +2,7 @@ autoware_pose_initializer - 0.39.0 + 0.40.0 The autoware_pose_initializer package Yamato Ando Takagi, Isamu diff --git a/localization/autoware_pose_instability_detector/CHANGELOG.rst b/localization/autoware_pose_instability_detector/CHANGELOG.rst index a02f1443d97e1..b95dcaf6f01c8 100644 --- a/localization/autoware_pose_instability_detector/CHANGELOG.rst +++ b/localization/autoware_pose_instability_detector/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_pose_instability_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_pose_instability_detector/package.xml b/localization/autoware_pose_instability_detector/package.xml index 2c982e30ca8d8..91a565446f9e9 100644 --- a/localization/autoware_pose_instability_detector/package.xml +++ b/localization/autoware_pose_instability_detector/package.xml @@ -2,7 +2,7 @@ autoware_pose_instability_detector - 0.39.0 + 0.40.0 The autoware_pose_instability_detector package Yamato Ando Kento Yabuuchi diff --git a/localization/autoware_stop_filter/CHANGELOG.rst b/localization/autoware_stop_filter/CHANGELOG.rst index 30e5b6169c154..f91a3b8de7f05 100644 --- a/localization/autoware_stop_filter/CHANGELOG.rst +++ b/localization/autoware_stop_filter/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_stop_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_stop_filter/package.xml b/localization/autoware_stop_filter/package.xml index 07ad7288c9d63..1ed5e2c2082be 100644 --- a/localization/autoware_stop_filter/package.xml +++ b/localization/autoware_stop_filter/package.xml @@ -2,7 +2,7 @@ autoware_stop_filter - 0.39.0 + 0.40.0 The stop filter package Yamato Ando Masahiro Sakamoto diff --git a/localization/autoware_twist2accel/CHANGELOG.rst b/localization/autoware_twist2accel/CHANGELOG.rst index ea50813677005..89b22e6ae4f26 100644 --- a/localization/autoware_twist2accel/CHANGELOG.rst +++ b/localization/autoware_twist2accel/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_twist2accel ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/autoware_twist2accel/package.xml b/localization/autoware_twist2accel/package.xml index 538a75f8f9474..75cea94546516 100644 --- a/localization/autoware_twist2accel/package.xml +++ b/localization/autoware_twist2accel/package.xml @@ -2,7 +2,7 @@ autoware_twist2accel - 0.39.0 + 0.40.0 The acceleration estimation package Yamato Ando Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_common/CHANGELOG.rst b/localization/yabloc/yabloc_common/CHANGELOG.rst index 7cdbceeb5a6a5..6812e5ca633ca 100644 --- a/localization/yabloc/yabloc_common/CHANGELOG.rst +++ b/localization/yabloc/yabloc_common/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package yabloc_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/yabloc/yabloc_common/package.xml b/localization/yabloc/yabloc_common/package.xml index 01b5a92745c3f..5a8f19ff16bd7 100644 --- a/localization/yabloc/yabloc_common/package.xml +++ b/localization/yabloc/yabloc_common/package.xml @@ -1,7 +1,7 @@ yabloc_common - 0.39.0 + 0.40.0 YabLoc common library Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_image_processing/CHANGELOG.rst b/localization/yabloc/yabloc_image_processing/CHANGELOG.rst index f6e619c8a62a6..bf4c1279fffdc 100644 --- a/localization/yabloc/yabloc_image_processing/CHANGELOG.rst +++ b/localization/yabloc/yabloc_image_processing/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package yabloc_image_processing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/yabloc/yabloc_image_processing/package.xml b/localization/yabloc/yabloc_image_processing/package.xml index 746e01f8e9841..c3202e8bfaebf 100644 --- a/localization/yabloc/yabloc_image_processing/package.xml +++ b/localization/yabloc/yabloc_image_processing/package.xml @@ -2,7 +2,7 @@ yabloc_image_processing - 0.39.0 + 0.40.0 YabLoc image processing package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_monitor/CHANGELOG.rst b/localization/yabloc/yabloc_monitor/CHANGELOG.rst index ea890d490ccfb..c7cb3c7dc307d 100644 --- a/localization/yabloc/yabloc_monitor/CHANGELOG.rst +++ b/localization/yabloc/yabloc_monitor/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package yabloc_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/yabloc/yabloc_monitor/package.xml b/localization/yabloc/yabloc_monitor/package.xml index ea7ce24f5da7c..1a0dbb6c7fdfa 100644 --- a/localization/yabloc/yabloc_monitor/package.xml +++ b/localization/yabloc/yabloc_monitor/package.xml @@ -2,7 +2,7 @@ yabloc_monitor - 0.39.0 + 0.40.0 YabLoc monitor package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst b/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst index 973e729089d7b..935aecb810449 100644 --- a/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst +++ b/localization/yabloc/yabloc_particle_filter/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package yabloc_particle_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/yabloc/yabloc_particle_filter/package.xml b/localization/yabloc/yabloc_particle_filter/package.xml index ac5ba4d30bb8a..074ff19334852 100644 --- a/localization/yabloc/yabloc_particle_filter/package.xml +++ b/localization/yabloc/yabloc_particle_filter/package.xml @@ -2,7 +2,7 @@ yabloc_particle_filter - 0.39.0 + 0.40.0 YabLoc particle filter package Kento Yabuuchi Masahiro Sakamoto diff --git a/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst b/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst index 2bae9b010e7f0..0b78a98bf07fd 100644 --- a/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst +++ b/localization/yabloc/yabloc_pose_initializer/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package yabloc_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - localization (`#9567 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(yabloc_pose_initializer): include opencv as system (`#9375 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/localization/yabloc/yabloc_pose_initializer/package.xml b/localization/yabloc/yabloc_pose_initializer/package.xml index 77fc397d207d4..4fd346f6327ad 100644 --- a/localization/yabloc/yabloc_pose_initializer/package.xml +++ b/localization/yabloc/yabloc_pose_initializer/package.xml @@ -1,7 +1,7 @@ yabloc_pose_initializer - 0.39.0 + 0.40.0 The pose initializer Kento Yabuuchi Masahiro Sakamoto diff --git a/map/autoware_lanelet2_map_visualizer/CHANGELOG.rst b/map/autoware_lanelet2_map_visualizer/CHANGELOG.rst new file mode 100644 index 0000000000000..3d95ca5f804b2 --- /dev/null +++ b/map/autoware_lanelet2_map_visualizer/CHANGELOG.rst @@ -0,0 +1,465 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package autoware_lanelet2_map_visualizer +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* Contributors: Fumiya Watanabe, Masaki Baba, Ryohsuke Mitsudome + +* Merge branch 'main' into release-0.40.0 +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* Contributors: Fumiya Watanabe, Masaki Baba, Ryohsuke Mitsudome + +0.39.0 (2024-11-25) +------------------- +* chore(package.xml): bump version to 0.39.0 (`#9435 `_) + * chore: update CODEOWNERS (`#9203 `_) + Co-authored-by: github-actions + * refactor(time_utils): prefix package and namespace with autoware (`#9173 `_) + * refactor(time_utils): prefix package and namespace with autoware + * refactor(time_utils): prefix package and namespace with autoware + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * feat(rtc_interface): add requested field (`#9202 `_) + * add requested feature + * Update planning/autoware_rtc_interface/test/test_rtc_interface.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + * fix(mpc_lateral_controller): correctly resample the MPC trajectory yaws (`#9199 `_) + * fix(bpp): prevent accessing nullopt (`#9204 `_) + fix(bpp): calcDistanceToRedTrafficLight null + * refactor(autoware_map_based_prediction): split pedestrian and bicycle predictor (`#9201 `_) + * refactor: grouping functions + * refactor: grouping parameters + * refactor: rename member road_users_history to road_users_history\_ + * refactor: separate util functions + * refactor: Add predictor_vru.cpp and utils.cpp to map_based_prediction_node + * refactor: Add explicit template instantiation for removeOldObjectsHistory function + * refactor: Add tf2_geometry_msgs to data_structure + * refactor: Remove unused variables and functions in map_based_prediction_node.cpp + * Update perception/autoware_map_based_prediction/include/map_based_prediction/predictor_vru.hpp + * Apply suggestions from code review + * style(pre-commit): autofix + --------- + Co-authored-by: Mamoru Sobue + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (`#8912 `_) + * Moved ndt_omp into ndt_scan_matcher + * Added Copyright + * style(pre-commit): autofix + * Fixed include + * Fixed cast style + * Fixed include + * Fixed honorific title + * Fixed honorific title + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed hierarchy + * Fixed NVTP to NVTL + * Added cspell:ignore + * Fixed miss spell + * style(pre-commit): autofix + * Fixed include + * Renamed applyFilter + * Moved ***_impl.hpp from include/ to src/ + * style(pre-commit): autofix + * Fixed variable scope + * Fixed to pass by reference + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * feat(autoware_test_utils): add traffic light msgs parser (`#9177 `_) + * fix(rtc_interface): update requested field for every cooperateStatus state (`#9211 `_) + * fix rtc_interface + * fix test condition + --------- + * feat(static_obstacle_avoidance): operator request for ambiguous vehicle (`#9205 `_) + * add operator request feature + * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + * feat(collision_detector): use polling subscriber (`#9213 `_) + use polling subscriber + * fix(diagnostic_graph_utils): reset graph when new one is received (`#9208 `_) + fix(diagnostic_graph_utils): reset graph when new one is reveived + * fix(autoware_ndt_scan_matcher): reduce initial_pose_estimation.particles_num from 200 to 100 on tests (`#9218 `_) + Reduced initial_pose_estimation.particles_num from 200 to 100 on tests + * feat(control_launch): add collision detector in launch (`#9214 `_) + add collision detector in launch + * chore(obstacle_cruise_planner): add function tests for a utils function (`#9206 `_) + * add utils test + --------- + * fix(bvp): remove expired module safely (`#9212 `_) + * fix(bvp): remove expired module safely + * fix: remove module id set + * fix: use itr to erase expired module + * fix: remove unused function + --------- + * test(bpp_common): add unit test for safety check (`#9223 `_) + * add test for object collision + * add test for more functions + * add docstring + * fix lane change + --------- + * fix(autoware_behavior_path_goal_planner_module): fix cppcheck unreadVariable (`#9192 `_) + * fix(autoware_image_projection_based_fusion): fix bugprone-misplaced-widening-cast (`#9229 `_) + * fix: bugprone-misplaced-widening-cast + * fix: clang-format + --------- + * fix(autoware_euclidean_cluster): fix bugprone-misplaced-widening-cast (`#9227 `_) + fix: bugprone-misplaced-widening-cast + * fix(autoware_image_projection_based_fusion): fix bugprone-misplaced-widening-cast (`#9226 `_) + * fix: bugprone-misplaced-widening-cast + * fix: clang-format + --------- + * fix(autoware_compare_map_segmentation): fix cppcheck constVariableReference (`#9196 `_) + * refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) + * fix(autoware_behavior_velocity_no_stopping_area_module): fix cppcheck knownConditionTrueFalse (`#9189 `_) + * fix(autoware_freespace_planning_algorithms): fix bugprone-unused-raii (`#9230 `_) + fix: bugprone-unused-raii + * refactor(map_based_prediction): divide objectsCallback (`#9219 `_) + * refactor(map_based_prediction): move member functions to utils (`#9225 `_) + * test(crosswalk): add unit test (`#9228 `_) + * fix(autoware_probabilistic_occupancy_grid_map): fix bugprone-incorrect-roundings (`#9221 `_) + fix: bugprone-incorrect-roundings + * refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) + * fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback (`#9234 `_) + * feat(autoware_motion_utils): add new trajectory class (`#8693 `_) + * feat(autoware_motion_utils): add interpolator + * use int32_t instead of int + * use int32_t instead of int + * use int32_t instead of int + * add const as much as possible and use `at()` in `vector` + * fix directory name + * refactor code and add example + * update + * remove unused include + * refactor code + * add clone function + * fix stairstep + * make constructor to public + * feat(autoware_motion_utils): add trajectory class + * Update CMakeLists.txt + * fix + * fix package.xml + * update crop + * revert crtp change + * update package.xml + * updating... + * update + * solve build problem + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * fix(autoware_image_projection_based_fusion): make optional to consider lens distortion in the point projection (`#9233 `_) + chore: add point_project_to_unrectified_image parameter to fusion_common.param.yaml + * feat(autoware_test_utils): add general topic dumper (`#9207 `_) + * fix(autoware_ekf_localizer): remove `timer_tf\_` (`#9244 `_) + Removed timer_tf\_ + * fix(autoware_rtc_interface): fix dependency (`#9237 `_) + * fix(autonomous_emergency_braking): solve issue with arc length (`#9247 `_) + * solve issue with arc length + * fix problem with points one vehicle apart from path + --------- + * fix(autoware_lidar_apollo_instance_segmentation): fix cppcheck suspiciousFloatingPointCast (`#9195 `_) + * fix(autoware_behavior_path_sampling_planner_module): fix cppcheck unusedVariable (`#9190 `_) + * refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) + * chore(autoware_geography_utils): update maintainers (`#9246 `_) + * update maintainers + * add author + --------- + * fix(lane_change): enable cancel when ego in turn direction lane (`#9124 `_) + * RT0-33893 add checks from prev intersection + * fix shadow variable + * fix logic + * update readme + * refactor get_ego_footprint + --------- + * fix(out_of_lane): correct calculations of the stop pose (`#9209 `_) + * fix(autoware_pointcloud_preprocessor): launch file load parameter from yaml (`#8129 `_) + * feat: fix launch file + * chore: fix spell error + * chore: fix parameters file name + * chore: remove filter base + --------- + * fix: missing dependency in common components (`#9072 `_) + * feat(autoware_trajectory): move trajectory_container from autoware_motion_utils to a new package (`#9253 `_) + * create trajectory container package + * update + * update + * style(pre-commit): autofix + * update codeowner + * update + * fix cmake + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * fix(autoware_pointcloud_preprocessor): fix the wrong naming of crop box parameter file (`#9258 `_) + fix: fix the wrong file name + * fix(dummy_diag_publisher): not use diagnostic_updater and param callback (`#9257 `_) + * fix(dummy_diag_publisher): not use diagnostic_updater and param callback for v0.29.0 (`#1414 `_) + fix(dummy_diag_publisher): not use diagnostic_updater and param callback + Co-authored-by: h-ohta + * fix: resolve build error of dummy diag publisher (`#1415 `_) + fix merge conflict + --------- + Co-authored-by: Shohei Sakai + Co-authored-by: h-ohta + * test(behavior_path_planner_common): add unit test for path shifter (`#9239 `_) + * add unit test for path shifter + * fix unnecessary modification + * fix spelling mistake + * add docstring + --------- + * feat(system_monitor): support loopback network interface (`#9067 `_) + * feat(system_monitor): support loopback network interface + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * feat(autoware_trajectory): change interface of InterpolatedArray (`#9264 `_) + change interface of InterpolateArray + * feat(system_monitor): add on/off config for network traffic monitor (`#9069 `_) + * feat(system_monitor): add config for network traffic monitor + * fix: change function name from stop to skip + --------- + * feat(detection_area)!: add retruction feature (`#9255 `_) + * fix(vehicle_cmd_gate): fix processing time measurement (`#9260 `_) + * fix(bvp): use polling subscriber (`#9242 `_) + * fix(bvp): use polling subscriber + * fix: use newest policy + --------- + * refactor(lane_change): remove std::optional from lanes polygon (`#9267 `_) + * fix(bpp): prevent accessing nullopt (`#9269 `_) + * refactor(lane_change): revert "remove std::optional from lanes polygon" (`#9272 `_) + Revert "refactor(lane_change): remove std::optional from lanes polygon (`#9267 `_)" + This reverts commit 0c70ea8793985c6aae90f851eeffdd2561fe04b3. + * feat(goal_planner): sort candidate path only when num to avoid is different (`#9271 `_) + * fix(/autoware_freespace_planning_algorithms): fix cppcheck unusedFunction (`#9274 `_) + * fix(autoware_behavior_path_start_planner_module): fix cppcheck unreadVariable (`#9277 `_) + * fix(autoware_ndt_scan_matcher): fix cppcheck unusedFunction (`#9275 `_) + * fix(autoware_pure_pursuit): fix cppcheck unusedFunction (`#9276 `_) + * fix(lane_change): correct computation of maximum lane changing length threshold (`#9279 `_) + fix computation of maximum lane changing length threshold + * feat(aeb): set global param to override autoware state check (`#9263 `_) + * set global param to override autoware state check + * change variable to be more general + * add comment + * move param to control component launch + * change param name to be more straightforward + --------- + * fix(autoware_default_adapi): change subscribing steering factor topic name for obstacle avoidance and lane changes (`#9273 `_) + feat(planning): add new steering factor topics for obstacle avoidance and lane changes + * chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- + * fix(lane_change): extending lane change path for multiple lane change (RT1-8427) (`#9268 `_) + * RT1-8427 extending lc path for multiple lc + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * fix(autoware_utils): address self-intersecting polygons in random_concave_generator and handle empty inners() during triangulation (`#8995 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * fix(behavior_path_planner_common): use boost intersects instead of overlaps (`#9289 `_) + * fix(behavior_path_planner_common): use boost intersects instead of overlaps + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp + Co-authored-by: Go Sakayori + --------- + Co-authored-by: Go Sakayori + * ci(.github): update image tags (`#9286 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- + * fix(autoware_mpc_lateral_controller): fix bugprone-misplaced-widening-cast (`#9224 `_) + * fix: bugprone-misplaced-widening-cast + * fix: consider negative values + --------- + * fix(autoware_detected_object_validation): fix clang-diagnostic-error (`#9215 `_) + fix: clang-c-error + * fix(autoware_detected_object_validation): fix bugprone-incorrect-roundings (`#9220 `_) + fix: bugprone-incorrect-roundings + * feat(autoware_test_utils): use sample_vehicle/sample_sensor_kit (`#9290 `_) + * refactor(lane_change): remove std::optional from lanes polygon (`#9288 `_) + * feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- + * feat(diagnostic_graph_aggregator): implement diagnostic graph dump functionality (`#9261 `_) + * chore(tvm_utility): remove tvm_utility package as it is no longer used (`#9291 `_) + * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) + * perf(autoware_ndt_scan_matcher): remove evecs\_, evals\_ of Leaf for memory efficiency (`#9281 `_) + * fix(lane_change): correct computation of maximum lane changing length threshold (`#9279 `_) + fix computation of maximum lane changing length threshold + * perf: remove evecs, evals from Leaf + * perf: remove evecs, evals from Leaf + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * test(costmap_generator): unit test implementation for costmap generator (`#9149 `_) + * modify costmap generator directory structure + * rename class CostmapGenerator to CostmapGeneratorNode + * unit test for object_map_utils + * catch error from lookupTransform + * use polling subscriber in costmap generator node + * add test for costmap generator node + * add test for isActive() + * revert unnecessary changes + * remove commented out line + * minor fix + * Update planning/autoware_costmap_generator/src/costmap_generator.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi + * fix(control): missing dependency in control components (`#9073 `_) + * test(autoware_control_evaluator): add unit test for utils autoware_control_evaluator (`#9307 `_) + * update unit test of control_evaluator. + * manual pre-commit. + --------- + * fix(collision_detector): skip process when odometry is not published (`#9308 `_) + * subscribe odometry + * fix precommit + * remove unnecessary log info + --------- + * feat(goal_planner): safety check with only parking path (`#9293 `_) + * refactor(goal_planner): remove reference_goal_pose getter/setter (`#9270 `_) + * feat(start_planner, lane_departure_checker): speed up by updating polygons (`#9309 `_) + speed up by updating polygons + * fix(autoware_trajectory): fix bug of autoware_trajectory (`#9314 `_) + * feat(autoware_trajectory): change default value of min_points (`#9315 `_) + * chore(codecov): update maintained packages (`#9316 `_) + * doc: fix links to design documents (`#9301 `_) + * fix(costmap_generator): use vehicle frame for lidar height thresholds (`#9311 `_) + * fix(tier4_dummy_object_rviz_plugin): fix missing dependency (`#9306 `_) + * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) + * add changelog + * update changelog + * fix version + * 0.39.0 + * refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- + * update version + --------- + Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]@users.noreply.github.com> + Co-authored-by: github-actions + Co-authored-by: Esteve Fernandez <33620+esteve@users.noreply.github.com> + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Go Sakayori + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> + Co-authored-by: Taekjin LEE + Co-authored-by: Mamoru Sobue + Co-authored-by: SakodaShintaro + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> + Co-authored-by: Yuki TAKAGI <141538661+yuki-takagi-66@users.noreply.github.com> + Co-authored-by: Ryuta Kambe + Co-authored-by: kobayu858 <129580202+kobayu858@users.noreply.github.com> + Co-authored-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> + Co-authored-by: danielsanchezaran + Co-authored-by: Yamato Ando + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + Co-authored-by: Yi-Hsiang Fang (Vivid) <146902905+vividf@users.noreply.github.com> + Co-authored-by: ぐるぐる + Co-authored-by: Shohei Sakai + Co-authored-by: h-ohta + Co-authored-by: iwatake + Co-authored-by: Kosuke Takeuchi + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + Co-authored-by: Kyoichi Sugahara + Co-authored-by: Giovanni Muhammad Raditya + Co-authored-by: Masato Saeki <78376491+MasatoSaeki@users.noreply.github.com> + Co-authored-by: Kem (TiankuiXian) <1041084556@qq.com> + Co-authored-by: Kento Osa <38522559+taisa1@users.noreply.github.com> + Co-authored-by: Masaki Baba +* Contributors: Yutaka Kondo + +0.38.0 (2024-11-11) +------------------- diff --git a/map/autoware_lanelet2_map_visualizer/package.xml b/map/autoware_lanelet2_map_visualizer/package.xml index 3c3bb24c18399..eef83f90ec142 100644 --- a/map/autoware_lanelet2_map_visualizer/package.xml +++ b/map/autoware_lanelet2_map_visualizer/package.xml @@ -2,7 +2,7 @@ autoware_lanelet2_map_visualizer - 0.1.0 + 0.40.0 The autoware_lanelet2_map_visualizer package Yamato Ando Ryu Yamamoto diff --git a/map/autoware_map_height_fitter/CHANGELOG.rst b/map/autoware_map_height_fitter/CHANGELOG.rst index 724ca70e2ec2d..d600473d9756f 100644 --- a/map/autoware_map_height_fitter/CHANGELOG.rst +++ b/map/autoware_map_height_fitter/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_map_height_fitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - map (`#9568 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/map/autoware_map_height_fitter/package.xml b/map/autoware_map_height_fitter/package.xml index 280ad1797a079..98a48704c0c4b 100644 --- a/map/autoware_map_height_fitter/package.xml +++ b/map/autoware_map_height_fitter/package.xml @@ -2,7 +2,7 @@ autoware_map_height_fitter - 0.39.0 + 0.40.0 The autoware_map_height_fitter package Takagi, Isamu Yamato Ando diff --git a/map/autoware_map_loader/CHANGELOG.rst b/map/autoware_map_loader/CHANGELOG.rst index 876670b13ca3d..a9e1080f1d6ec 100644 --- a/map/autoware_map_loader/CHANGELOG.rst +++ b/map/autoware_map_loader/CHANGELOG.rst @@ -2,6 +2,45 @@ Changelog for package autoware_map_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - map (`#9568 `_) +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* fix: fix package names in changelog files (`#9500 `_) +* update version +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masaki Baba, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/map/autoware_map_loader/package.xml b/map/autoware_map_loader/package.xml index 48e3b6efdaa13..4d4eabc6e3f25 100644 --- a/map/autoware_map_loader/package.xml +++ b/map/autoware_map_loader/package.xml @@ -2,7 +2,7 @@ autoware_map_loader - 0.39.0 + 0.40.0 The autoware_map_loader package Yamato Ando Ryu Yamamoto diff --git a/map/autoware_map_projection_loader/CHANGELOG.rst b/map/autoware_map_projection_loader/CHANGELOG.rst index b0e85cc682510..eef30e5c5f159 100644 --- a/map/autoware_map_projection_loader/CHANGELOG.rst +++ b/map/autoware_map_projection_loader/CHANGELOG.rst @@ -2,6 +2,55 @@ Changelog for package autoware_map_projection_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - map (`#9568 `_) +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masaki Baba, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/map/autoware_map_projection_loader/package.xml b/map/autoware_map_projection_loader/package.xml index 7ce0cbb8105a7..ad31dfdcc094d 100644 --- a/map/autoware_map_projection_loader/package.xml +++ b/map/autoware_map_projection_loader/package.xml @@ -2,7 +2,7 @@ autoware_map_projection_loader - 0.39.0 + 0.40.0 autoware_map_projection_loader package as a ROS 2 node Yamato Ando Masahiro Sakamoto diff --git a/map/autoware_map_tf_generator/CHANGELOG.rst b/map/autoware_map_tf_generator/CHANGELOG.rst index 18bde0c6a0106..963e450bd4856 100644 --- a/map/autoware_map_tf_generator/CHANGELOG.rst +++ b/map/autoware_map_tf_generator/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_map_tf_generator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - map (`#9568 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/map/autoware_map_tf_generator/package.xml b/map/autoware_map_tf_generator/package.xml index 9a5e0388e08b9..0e81321daea2e 100644 --- a/map/autoware_map_tf_generator/package.xml +++ b/map/autoware_map_tf_generator/package.xml @@ -2,7 +2,7 @@ autoware_map_tf_generator - 0.39.0 + 0.40.0 map_tf_generator package as a ROS 2 node Yamato Ando Kento Yabuuchi diff --git a/perception/autoware_bytetrack/CHANGELOG.rst b/perception/autoware_bytetrack/CHANGELOG.rst index 7b18570598431..2db62f9a4e374 100644 --- a/perception/autoware_bytetrack/CHANGELOG.rst +++ b/perception/autoware_bytetrack/CHANGELOG.rst @@ -2,6 +2,40 @@ Changelog for package autoware_bytetrack ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat(bytetrack): remove unreachable code block from lapjv.h (`#9563 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_bytetrack): update visualizer param path and not to set default value (`#9490 `_) + fix: update visualizer param path and not to set default value +* fix(autoware_bytetrack): fix clang-diagnostic-implicit-const-int-float-conversion (`#9513 `_) + fix: clang-diagnostic-implicit-const-int-float-conversion +* fix(autoware_bytetrack): fix clang-diagnostic-implicit-const-int-float-conversion (`#9468 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kotaro Uetake, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_bytetrack/package.xml b/perception/autoware_bytetrack/package.xml index 0cb0747fff40a..4dc982595c588 100644 --- a/perception/autoware_bytetrack/package.xml +++ b/perception/autoware_bytetrack/package.xml @@ -2,7 +2,7 @@ autoware_bytetrack - 0.39.0 + 0.40.0 ByteTrack implementation ported toward Autoware Manato HIRABAYASHI Yoshi RI diff --git a/perception/autoware_cluster_merger/CHANGELOG.rst b/perception/autoware_cluster_merger/CHANGELOG.rst index 9e1d2b9d0caff..1acdbf9333f30 100644 --- a/perception/autoware_cluster_merger/CHANGELOG.rst +++ b/perception/autoware_cluster_merger/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_cluster_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_cluster_merger/package.xml b/perception/autoware_cluster_merger/package.xml index 29cbe8b5be016..92e1a8aadf40c 100644 --- a/perception/autoware_cluster_merger/package.xml +++ b/perception/autoware_cluster_merger/package.xml @@ -2,7 +2,7 @@ autoware_cluster_merger - 0.39.0 + 0.40.0 The ROS 2 cluster merger package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_compare_map_segmentation/CHANGELOG.rst b/perception/autoware_compare_map_segmentation/CHANGELOG.rst index b45f1b3e64076..8d784ca304874 100644 --- a/perception/autoware_compare_map_segmentation/CHANGELOG.rst +++ b/perception/autoware_compare_map_segmentation/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_compare_map_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(compare_map_segmentation): rename defined type (`#9181 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(compare_map_segmentation): add maintainer (`#9371 `_) +* fix(compare_map_segmentation): timer period mismatched with parameter (`#9259 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_compare_map_segmentation): fix cppcheck constVariableReference (`#9196 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo, badai nguyen + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_compare_map_segmentation/package.xml b/perception/autoware_compare_map_segmentation/package.xml index b25ca8bfd829d..8c07d29156f8a 100644 --- a/perception/autoware_compare_map_segmentation/package.xml +++ b/perception/autoware_compare_map_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_compare_map_segmentation - 0.39.0 + 0.40.0 The ROS 2 autoware_compare_map_segmentation package amc-nu Yukihiro Saito diff --git a/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst b/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst index e4a85d38559b0..34e514d13e007 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst +++ b/perception/autoware_crosswalk_traffic_light_estimator/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_crosswalk_traffic_light_estimator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masato Saeki, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_crosswalk_traffic_light_estimator/package.xml b/perception/autoware_crosswalk_traffic_light_estimator/package.xml index 12e689b5b50e3..a760c3bd950e3 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/package.xml +++ b/perception/autoware_crosswalk_traffic_light_estimator/package.xml @@ -1,7 +1,7 @@ autoware_crosswalk_traffic_light_estimator - 0.39.0 + 0.40.0 The autoware_crosswalk_traffic_light_estimator package Satoshi Ota diff --git a/perception/autoware_detected_object_feature_remover/CHANGELOG.rst b/perception/autoware_detected_object_feature_remover/CHANGELOG.rst index 2f887760e3970..f0d4f1f746eaa 100644 --- a/perception/autoware_detected_object_feature_remover/CHANGELOG.rst +++ b/perception/autoware_detected_object_feature_remover/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_detected_object_feature_remover ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_detected_object_feature_remover/package.xml b/perception/autoware_detected_object_feature_remover/package.xml index 45f7d6e9036e7..a112598728614 100644 --- a/perception/autoware_detected_object_feature_remover/package.xml +++ b/perception/autoware_detected_object_feature_remover/package.xml @@ -2,7 +2,7 @@ autoware_detected_object_feature_remover - 0.39.0 + 0.40.0 The autoware_detected_object_feature_remover package Tomoya Kimura Yoshi Ri diff --git a/perception/autoware_detected_object_validation/CHANGELOG.rst b/perception/autoware_detected_object_validation/CHANGELOG.rst index ebe5562fc2ec0..bde610a8e3fd5 100644 --- a/perception/autoware_detected_object_validation/CHANGELOG.rst +++ b/perception/autoware_detected_object_validation/CHANGELOG.rst @@ -2,6 +2,55 @@ Changelog for package autoware_detected_object_validation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* feat(object_lanelet_filter): add configurable margin for object lanel… (`#9240 `_) + * feat(object_lanelet_filter): add configurable margin for object lanelet filter + modified: perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp + * feat(object_lanelet_filter): add condition to check wheter polygon is empty in debug mode + * feat(object_lanelet_filter): fix cppcheck + * fix: brig back missing type definition + * feat: add stop watch for processing time in object lanelet filter + * feat(object_lanelet_filter): remove extra comment line + * feat(_object_lanelet_filter): udpate readme + * style(pre-commit): autofix + * Update perception/autoware_detected_object_validation/src/lanelet_filter/debug.cpp + Co-authored-by: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> + * style(pre-commit): autofix + --------- + Co-authored-by: Sebastian Zęderowski + Co-authored-by: Taekjin LEE + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_detected_object_validation): fix bugprone-incorrect-roundings (`#9220 `_) + fix: bugprone-incorrect-roundings +* fix(autoware_detected_object_validation): fix clang-diagnostic-error (`#9215 `_) + fix: clang-c-error +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Sebastian Zęderowski, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_detected_object_validation/package.xml b/perception/autoware_detected_object_validation/package.xml index 777fcea4db226..9aa6f018de5fa 100644 --- a/perception/autoware_detected_object_validation/package.xml +++ b/perception/autoware_detected_object_validation/package.xml @@ -2,7 +2,7 @@ autoware_detected_object_validation - 0.39.0 + 0.40.0 The ROS 2 detected_object_validation package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_detection_by_tracker/CHANGELOG.rst b/perception/autoware_detection_by_tracker/CHANGELOG.rst index 98d6dbe40f4a6..dd8a44828a5ff 100644 --- a/perception/autoware_detection_by_tracker/CHANGELOG.rst +++ b/perception/autoware_detection_by_tracker/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_detection_by_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_detection_by_tracker/package.xml b/perception/autoware_detection_by_tracker/package.xml index cee180ba43c29..b9ee4fa2aac71 100644 --- a/perception/autoware_detection_by_tracker/package.xml +++ b/perception/autoware_detection_by_tracker/package.xml @@ -2,7 +2,7 @@ autoware_detection_by_tracker - 0.39.0 + 0.40.0 The ROS 2 autoware_detection_by_tracker package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_elevation_map_loader/CHANGELOG.rst b/perception/autoware_elevation_map_loader/CHANGELOG.rst index bd4d313348d9b..b53c69f07a8a9 100644 --- a/perception/autoware_elevation_map_loader/CHANGELOG.rst +++ b/perception/autoware_elevation_map_loader/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_elevation_map_loader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(autoware_elevation_map_loader): fix clang-diagnostic-format-security (`#9492 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_elevation_map_loader/package.xml b/perception/autoware_elevation_map_loader/package.xml index 9a63c2fa569cc..6839cd60e2990 100644 --- a/perception/autoware_elevation_map_loader/package.xml +++ b/perception/autoware_elevation_map_loader/package.xml @@ -2,7 +2,7 @@ autoware_elevation_map_loader - 0.39.0 + 0.40.0 The autoware_elevation_map_loader package Kosuke Takeuchi Taichi Higashide diff --git a/perception/autoware_euclidean_cluster/CHANGELOG.rst b/perception/autoware_euclidean_cluster/CHANGELOG.rst index 9702b99a0b643..b7ce92ddd6510 100644 --- a/perception/autoware_euclidean_cluster/CHANGELOG.rst +++ b/perception/autoware_euclidean_cluster/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_euclidean_cluster ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_euclidean_cluster): fix bugprone-misplaced-widening-cast (`#9227 `_) + fix: bugprone-misplaced-widening-cast +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_euclidean_cluster/package.xml b/perception/autoware_euclidean_cluster/package.xml index d740c35fbd94d..f4568baaea19b 100644 --- a/perception/autoware_euclidean_cluster/package.xml +++ b/perception/autoware_euclidean_cluster/package.xml @@ -2,7 +2,7 @@ autoware_euclidean_cluster - 0.39.0 + 0.40.0 The autoware_euclidean_cluster package Yukihiro Saito Dai Nguyen diff --git a/perception/autoware_ground_segmentation/CHANGELOG.rst b/perception/autoware_ground_segmentation/CHANGELOG.rst index 7c2dbb7a2413c..b23cfa4972f1f 100644 --- a/perception/autoware_ground_segmentation/CHANGELOG.rst +++ b/perception/autoware_ground_segmentation/CHANGELOG.rst @@ -2,6 +2,123 @@ Changelog for package autoware_ground_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_ground_segmentation): remove unused function (`#9536 `_) +* fix(autoware_ground_segmentation): fix clang-diagnostic-inconsistent-missing-override (`#9517 `_) + * fix: clang-diagnostic-inconsistent-missing-override + * fix: pre-commit error + --------- +* feat(autoware_ground_segmentation): grid data structure revision for efficiency improvement (`#9297 `_) + * fix: replace point index to data index + * feat: Use emplace_back instead of push_back for adding gnd_grids in node.cpp + * fix: prep for non-sorted grid process + * feat: Add Cell class and Grid class for grid-based segmentation + * refactor: Add Cell and Grid classes for grid-based segmentation + * feat: initialize new grid + * refactor: Update Grid class initialization to use radians for azimuth size + refactor: Update Grid class initialization to use radians for azimuth size + refactor: Update Grid class initialization to use radians for azimuth size + * refactor: Fix calculation of azimuth index in Grid class + * feat: implement grid based segmentation, temporary logic + * refactor: idx position convert methods + * refactor: Update Grid class initialization to use radians for azimuth size + * feat: reconnect grids filled + * feat: grid initialization + * refactor: Update Grid class initialization and reset methods, implement a segmentation logic + refactor: Update Grid class initialization and reset methods, implement a segmentation logic + refactor: replace original methods + * feat: add time_keeper + * refactor: add time keeper in grid class + refactor: remove previous scan ground grid + * refactor: optimize grid boundary calculations and use squared values for radius comparisons + * fix: use pointer for prev cell + * refactor: remove time keeper called too many times + * fix: radial idx estimation fix + * refactor: optimize ground bin average calculation + fix: ground bin logic fix + * refactor: make grid ground filter separate + * refactor: remove unused code + fix: azimuth grid index converter bug + * fix: segmentation logic determination fix + fix: cell connection bug fix + * refactor: optimize pseudoArcTan2 function + * refactor: update grid radial calculation + * refactor: contain input cloud ptr + * refactor: separate ground initialization + * refactor: Remove unused code and optimize grid radial calculation + * refactor: Inline functions for improved performance + * feat: various azimuth interval per radial distance + * refactor: Fix bug in grid ground filter segmentation logic and cell connection + Remove unused code and optimize grid radial calculation + * fix: add missing offset calculation + * refactor: Improve grid ground filter segmentation logic and cell connection + Optimize grid radial calculation and remove unused code + * refactor: Remove debug print statements and optimize grid initialization + * refactor: Update grid radial limit to 200.0m + * refactor: Update grid size to 0.5m for improved ground segmentation + * refactor: Improve grid ground filter segmentation logic + * refactor: Optimize grid ground filter segmentation logic + * refactor: Update logic order for fast segmentation + * fix: resolve cppcheck issue + * fix: pseudo atan2 fix for even distribution of azimuth + * fix: remove unused next_grid_idx\_ update + * fix: introduce pseudo tangent to match result of pseudo arc tangent + * style(pre-commit): autofix + * fix: limit gradient + * fix: bring previous average when the ground bin is empty + * fix: back to constant azimuth interval grid + * perf: remove division for efficiency + * perf: remove division for efficiency + * perf: contain radius and height to avoid double calculation + * perf: optimize grid distance calculation for efficiency + * style(pre-commit): autofix + * perf: using isEmpty for efficiency + * chore: initialization fix + * perf: initial ground cell is integrated into the classify method for efficiency + * perf: refactor grid initialization for efficiency + * perf: optimize grid cell linking for efficiency + * Revert "perf: initial ground cell is integrated into the classify method for efficiency" + This reverts commit a4ab70b630f966d3e2827a07a0ec27079ecc78d2. + * fix: fix pseudo atan2 bug + * feat: various azimuth interval by range + * perf: optimize pseudoArcTan2 function for efficiency + * style(pre-commit): autofix + * fix: avoid zero division on the slope estimation + * fix: limit recursive search + refactor: improve efficiency of recursiveSearch function + Fix function parameter type in GridGroundFilter + * refactor: add comments about unclassified case + * chore: add comment to explain methods + * refactor: remove unnecessary include statement + * refactor: cast point_list size to int in getPointNum method + * refactor: add index check in getCell method + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Taekjin LEE, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_ground_segmentation/package.xml b/perception/autoware_ground_segmentation/package.xml index 3ac3047654a96..1cb179970e1ae 100644 --- a/perception/autoware_ground_segmentation/package.xml +++ b/perception/autoware_ground_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_ground_segmentation - 0.39.0 + 0.40.0 The ROS 2 autoware_ground_segmentation package amc-nu Yukihiro Saito diff --git a/perception/autoware_image_projection_based_fusion/CHANGELOG.rst b/perception/autoware_image_projection_based_fusion/CHANGELOG.rst index 87d1bc0c2d687..f0a39ef78c708 100644 --- a/perception/autoware_image_projection_based_fusion/CHANGELOG.rst +++ b/perception/autoware_image_projection_based_fusion/CHANGELOG.rst @@ -2,6 +2,78 @@ Changelog for package autoware_image_projection_based_fusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix(lidar_centerpoint): non-maximum suppression target decision logic (`#9595 `_) + * refactor(lidar_centerpoint): optimize non-maximum suppression search distance calculation + * feat(lidar_centerpoint): do not suppress if one side of the object is pedestrian + * style(pre-commit): autofix + * refactor(lidar_centerpoint): remove unused variables + * refactor: remove unused variables + fix: implement non-maximum suppression logic to the transfusion + refactor: remove unused parameter iou_nms_target_class_names + Revert "fix: implement non-maximum suppression logic to the transfusion" + This reverts commit b8017fc366ec7d67234445ef5869f8beca9b6f45. + fix: revert transfusion modification + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* feat: remove max rois limit in the image projection based fusion (`#9596 `_) + feat: remove max rois limit +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(autoware_image_projection_based_fusion): detected object roi box projection fix (`#9519 `_) + * fix: detected object roi box projection fix + 1. eliminate misuse of std::numeric_limits::min() + 2. fix roi range up to the image edges + * fix: fix roi range calculation in RoiDetectedObjectFusionNode + Improve the calculation of the region of interest (ROI) in the RoiDetectedObjectFusionNode. The previous code had an issue where the ROI range was not correctly limited to the image edges. This fix ensures that the ROI is within the image boundaries by using the correct comparison operators for the x and y coordinates. + --------- +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* ci(pre-commit): update cpplint to 2.0.0 (`#9557 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* chore(image_projection_based_fusion): add debug for roi_pointcloud fusion (`#9481 `_) +* fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (`#9509 `_) +* fix(autoware_image_projection_based_fusion): fix clang-diagnostic-unused-private-field (`#9505 `_) +* fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (`#9495 `_) +* fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (`#9516 `_) + fix: clang-diagnostic-inconsistent-missing-override +* fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (`#9510 `_) +* fix(autoware_image_projection_based_fusion): fix clang-diagnostic-unused-private-field (`#9473 `_) + * fix: clang-diagnostic-unused-private-field + * fix: build error + --------- +* fix(autoware_image_projection_based_fusion): fix clang-diagnostic-inconsistent-missing-override (`#9472 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_image_projection_based_fusion): make optional to consider lens distortion in the point projection (`#9233 `_) + chore: add point_project_to_unrectified_image parameter to fusion_common.param.yaml +* fix(autoware_image_projection_based_fusion): fix bugprone-misplaced-widening-cast (`#9226 `_) + * fix: bugprone-misplaced-widening-cast + * fix: clang-format + --------- +* fix(autoware_image_projection_based_fusion): fix bugprone-misplaced-widening-cast (`#9229 `_) + * fix: bugprone-misplaced-widening-cast + * fix: clang-format + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Taekjin LEE, Yoshi Ri, Yutaka Kondo, awf-autoware-bot[bot], badai nguyen, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_image_projection_based_fusion/package.xml b/perception/autoware_image_projection_based_fusion/package.xml index 70aa2246d1cdf..025ed5377fa72 100644 --- a/perception/autoware_image_projection_based_fusion/package.xml +++ b/perception/autoware_image_projection_based_fusion/package.xml @@ -2,7 +2,7 @@ autoware_image_projection_based_fusion - 0.39.0 + 0.40.0 The autoware_image_projection_based_fusion package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst b/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst index e55a52d6924d5..5841ae3059503 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst +++ b/perception/autoware_lidar_apollo_instance_segmentation/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_lidar_apollo_instance_segmentation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_lidar_apollo_instance_segmentation): fix cppcheck suspiciousFloatingPointCast (`#9195 `_) +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_lidar_apollo_instance_segmentation/package.xml b/perception/autoware_lidar_apollo_instance_segmentation/package.xml index dd48f1a2844d4..8a3d5a7ea6f76 100755 --- a/perception/autoware_lidar_apollo_instance_segmentation/package.xml +++ b/perception/autoware_lidar_apollo_instance_segmentation/package.xml @@ -2,7 +2,7 @@ autoware_lidar_apollo_instance_segmentation - 0.39.0 + 0.40.0 autoware_lidar_apollo_instance_segmentation Yoshi Ri Yukihiro Saito diff --git a/perception/autoware_lidar_centerpoint/CHANGELOG.rst b/perception/autoware_lidar_centerpoint/CHANGELOG.rst index b10fd533af90f..46f68e7462377 100644 --- a/perception/autoware_lidar_centerpoint/CHANGELOG.rst +++ b/perception/autoware_lidar_centerpoint/CHANGELOG.rst @@ -2,6 +2,52 @@ Changelog for package autoware_lidar_centerpoint ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix(lidar_centerpoint): non-maximum suppression target decision logic (`#9595 `_) + * refactor(lidar_centerpoint): optimize non-maximum suppression search distance calculation + * feat(lidar_centerpoint): do not suppress if one side of the object is pedestrian + * style(pre-commit): autofix + * refactor(lidar_centerpoint): remove unused variables + * refactor: remove unused variables + fix: implement non-maximum suppression logic to the transfusion + refactor: remove unused parameter iou_nms_target_class_names + Revert "fix: implement non-maximum suppression logic to the transfusion" + This reverts commit b8017fc366ec7d67234445ef5869f8beca9b6f45. + fix: revert transfusion modification + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_lidar_centerpoint): fix clang-diagnostic-delete-abstract-non-virtual-dtor (`#9515 `_) +* feat(autoware_lidar_centerpoint): added a check to notify if we are dropping pillars (`#9488 `_) + * feat: added a check to notify if we are dropping pillars + * chore: updated text + * chore: throttled the message + --------- +* fix(autoware_lidar_centerpoint): fix clang-diagnostic-unused-private-field (`#9471 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kenzo Lobos Tsunekawa, M. Fatih Cırıt, Ryohsuke Mitsudome, Taekjin LEE, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_lidar_centerpoint/package.xml b/perception/autoware_lidar_centerpoint/package.xml index 9734e56a29d57..78e900f8198f6 100644 --- a/perception/autoware_lidar_centerpoint/package.xml +++ b/perception/autoware_lidar_centerpoint/package.xml @@ -2,7 +2,7 @@ autoware_lidar_centerpoint - 0.39.0 + 0.40.0 The autoware_lidar_centerpoint package Kenzo Lobos-Tsunekawa Koji Minoda diff --git a/perception/autoware_lidar_transfusion/CHANGELOG.rst b/perception/autoware_lidar_transfusion/CHANGELOG.rst index 94f49d65991c8..f397c9e1ddc06 100644 --- a/perception/autoware_lidar_transfusion/CHANGELOG.rst +++ b/perception/autoware_lidar_transfusion/CHANGELOG.rst @@ -2,6 +2,39 @@ Changelog for package autoware_lidar_transfusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix(autoware_lidar_transfusion): non-maximum suppression target decision logic (`#9612 `_) + fix: non-maximum suppression target decision logic +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* chore(autoware_lidar_transfusion): added a warning if we are dropping voxels (`#9486 `_) + * chore: added a warning if we are dropping voxels + * chore: changed the warning to a throttled one + --------- +* fix(autoware_lidar_transfusion): fix clang-diagnostic-unused-private-field (`#9499 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kenzo Lobos Tsunekawa, M. Fatih Cırıt, Ryohsuke Mitsudome, Taekjin LEE, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_lidar_transfusion/package.xml b/perception/autoware_lidar_transfusion/package.xml index a4dd66c27db0e..d9c43bc5a1b20 100644 --- a/perception/autoware_lidar_transfusion/package.xml +++ b/perception/autoware_lidar_transfusion/package.xml @@ -2,7 +2,7 @@ autoware_lidar_transfusion - 0.39.0 + 0.40.0 The lidar_transfusion package Amadeusz Szymko Kenzo Lobos-Tsunekawa diff --git a/perception/autoware_map_based_prediction/CHANGELOG.rst b/perception/autoware_map_based_prediction/CHANGELOG.rst index 69769df3aa04d..55bc24894c230 100644 --- a/perception/autoware_map_based_prediction/CHANGELOG.rst +++ b/perception/autoware_map_based_prediction/CHANGELOG.rst @@ -2,6 +2,51 @@ Changelog for package autoware_map_based_prediction ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_map_based_prediction): msg namespace (`#9553 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(map_based_prediction): move member functions to utils (`#9225 `_) +* refactor(map_based_prediction): divide objectsCallback (`#9219 `_) +* refactor(autoware_map_based_prediction): split pedestrian and bicycle predictor (`#9201 `_) + * refactor: grouping functions + * refactor: grouping parameters + * refactor: rename member road_users_history to road_users_history\_ + * refactor: separate util functions + * refactor: Add predictor_vru.cpp and utils.cpp to map_based_prediction_node + * refactor: Add explicit template instantiation for removeOldObjectsHistory function + * refactor: Add tf2_geometry_msgs to data_structure + * refactor: Remove unused variables and functions in map_based_prediction_node.cpp + * Update perception/autoware_map_based_prediction/include/map_based_prediction/predictor_vru.hpp + * Apply suggestions from code review + * style(pre-commit): autofix + --------- + Co-authored-by: Mamoru Sobue + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Amadeusz Szymko, Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Taekjin LEE, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_map_based_prediction/package.xml b/perception/autoware_map_based_prediction/package.xml index 3d7cba491fe0e..9012590a45b14 100644 --- a/perception/autoware_map_based_prediction/package.xml +++ b/perception/autoware_map_based_prediction/package.xml @@ -2,7 +2,7 @@ autoware_map_based_prediction - 0.39.0 + 0.40.0 This package implements a map_based_prediction Tomoya Kimura Yoshi Ri diff --git a/perception/autoware_multi_object_tracker/CHANGELOG.rst b/perception/autoware_multi_object_tracker/CHANGELOG.rst index 5f8ee4ef00869..5fced913f2b9d 100644 --- a/perception/autoware_multi_object_tracker/CHANGELOG.rst +++ b/perception/autoware_multi_object_tracker/CHANGELOG.rst @@ -2,6 +2,57 @@ Changelog for package autoware_multi_object_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(autoware_multi_object_tracker): measure latency with latest detection update time (`#9533 `_) + * fix: measure latency with latest detection update time + * fix: remove duplicated current_time + --------- +* fix(cpplint): include what you use - perception (`#9569 `_) +* ci(pre-commit): autoupdate (`#8949 `_) + Co-authored-by: M. Fatih Cırıt +* fix(autoware_multi_object_tracker): fix clang-diagnostic-unused-private-field (`#9491 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(autoware_multi_object_tracker): new function to add odometry uncertainty (`#9139 `_) + * feat: add Odometry uncertainty to object tracking + * feat: Add odometry heading uncertainty to object pose covariance + feat: Rotate object pose covariance matrix to account for yaw uncertainty + Rotate the object pose covariance matrix in the uncertainty_processor.cpp file to account for the yaw uncertainty. This ensures that the covariance matrix accurately represents the position uncertainty of the object. + Refactor the code to rotate the covariance matrix using Eigen's Rotation2D class. The yaw uncertainty is added to the y-y element of the rotated covariance matrix. Finally, update the object_pose_cov array with the updated covariance values. + Closes `#123 `_ + * feat: Add odometry motion uncertainty to object pose covariance + refactoring + * feat: Update ego twist uncertainty to the object velocity uncertainty + * feat: update object twist covariance by odometry yaw rate uncertainty + * feat: move uncertainty modeling to input side + * feat: add option to select odometry uncertainty + * refactor: rename consider_odometry_uncertainty to enable_odometry_uncertainty + * fix: transform to world first, add odometry covariance later + style(pre-commit): autofix + * feat: Add odometry heading uncertainty to object pose covariance + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Taekjin LEE, Yutaka Kondo, awf-autoware-bot[bot], kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_multi_object_tracker/package.xml b/perception/autoware_multi_object_tracker/package.xml index aa5c4968e36f9..912165d7b6ab6 100644 --- a/perception/autoware_multi_object_tracker/package.xml +++ b/perception/autoware_multi_object_tracker/package.xml @@ -2,7 +2,7 @@ autoware_multi_object_tracker - 0.39.0 + 0.40.0 The ROS 2 autoware_multi_object_tracker package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_merger/CHANGELOG.rst b/perception/autoware_object_merger/CHANGELOG.rst index 2e1adbb4b8be6..004d56c406ce9 100644 --- a/perception/autoware_object_merger/CHANGELOG.rst +++ b/perception/autoware_object_merger/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_object_merger/package.xml b/perception/autoware_object_merger/package.xml index 84a9ec64cf3f0..481bb0babf20d 100644 --- a/perception/autoware_object_merger/package.xml +++ b/perception/autoware_object_merger/package.xml @@ -2,7 +2,7 @@ autoware_object_merger - 0.39.0 + 0.40.0 The autoware_object_merger package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_range_splitter/CHANGELOG.rst b/perception/autoware_object_range_splitter/CHANGELOG.rst index b0f2a81744b8e..2ad998b66391f 100644 --- a/perception/autoware_object_range_splitter/CHANGELOG.rst +++ b/perception/autoware_object_range_splitter/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_object_range_splitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_object_range_splitter/package.xml b/perception/autoware_object_range_splitter/package.xml index 27503850261d5..bfc8470834443 100644 --- a/perception/autoware_object_range_splitter/package.xml +++ b/perception/autoware_object_range_splitter/package.xml @@ -2,7 +2,7 @@ autoware_object_range_splitter - 0.39.0 + 0.40.0 The autoware_object_range_splitter package Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_object_velocity_splitter/CHANGELOG.rst b/perception/autoware_object_velocity_splitter/CHANGELOG.rst index 9d38280224125..ec69fb1754d3b 100644 --- a/perception/autoware_object_velocity_splitter/CHANGELOG.rst +++ b/perception/autoware_object_velocity_splitter/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_object_velocity_splitter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_object_velocity_splitter/package.xml b/perception/autoware_object_velocity_splitter/package.xml index 48ffa93f05102..681b29b0c49e8 100644 --- a/perception/autoware_object_velocity_splitter/package.xml +++ b/perception/autoware_object_velocity_splitter/package.xml @@ -2,7 +2,7 @@ autoware_object_velocity_splitter - 0.39.0 + 0.40.0 autoware_object_velocity_splitter Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst b/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst index e020be4cc906a..cf7dc5752c62d 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst +++ b/perception/autoware_occupancy_grid_map_outlier_filter/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_occupancy_grid_map_outlier_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_occupancy_grid_map_outlier_filter): fix bugprone-incorrect-roundings (`#9217 `_) + * fix: bugprone-incorrect-roundings + * fix: clang-format + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_occupancy_grid_map_outlier_filter/package.xml b/perception/autoware_occupancy_grid_map_outlier_filter/package.xml index c8c1f15f72c0d..fba074fdc669f 100644 --- a/perception/autoware_occupancy_grid_map_outlier_filter/package.xml +++ b/perception/autoware_occupancy_grid_map_outlier_filter/package.xml @@ -2,7 +2,7 @@ autoware_occupancy_grid_map_outlier_filter - 0.39.0 + 0.40.0 The ROS 2 occupancy_grid_map_outlier_filter package amc-nu Yukihiro Saito diff --git a/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst b/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst index 6668ef1c29ed9..75d579b612168 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst +++ b/perception/autoware_probabilistic_occupancy_grid_map/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_probabilistic_occupancy_grid_map ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_probabilistic_occupancy_grid_map): fix bugprone-incorrect-roundings (`#9221 `_) + fix: bugprone-incorrect-roundings +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_probabilistic_occupancy_grid_map/package.xml b/perception/autoware_probabilistic_occupancy_grid_map/package.xml index e5bd0eebb9b2e..ece7ef0dec663 100644 --- a/perception/autoware_probabilistic_occupancy_grid_map/package.xml +++ b/perception/autoware_probabilistic_occupancy_grid_map/package.xml @@ -2,7 +2,7 @@ autoware_probabilistic_occupancy_grid_map - 0.39.0 + 0.40.0 generate probabilistic occupancy grid map Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst b/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst index 8eb064446cbba..ff859a4d44ce3 100644 --- a/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst +++ b/perception/autoware_radar_crossing_objects_noise_filter/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_radar_crossing_objects_noise_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* docs: update the list styles (`#9555 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_radar_crossing_objects_noise_filter/package.xml b/perception/autoware_radar_crossing_objects_noise_filter/package.xml index 5536033aa1319..f5900066cb10b 100644 --- a/perception/autoware_radar_crossing_objects_noise_filter/package.xml +++ b/perception/autoware_radar_crossing_objects_noise_filter/package.xml @@ -2,7 +2,7 @@ autoware_radar_crossing_objects_noise_filter - 0.39.0 + 0.40.0 autoware_radar_crossing_objects_noise_filter Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst b/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst index 9c4e7c527ecb7..f6f48dfe36231 100644 --- a/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst +++ b/perception/autoware_radar_fusion_to_detected_object/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_radar_fusion_to_detected_object ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_radar_fusion_to_detected_object/package.xml b/perception/autoware_radar_fusion_to_detected_object/package.xml index 82f2f0926e929..20d6331dc8a37 100644 --- a/perception/autoware_radar_fusion_to_detected_object/package.xml +++ b/perception/autoware_radar_fusion_to_detected_object/package.xml @@ -2,7 +2,7 @@ autoware_radar_fusion_to_detected_object - 0.39.0 + 0.40.0 autoware_radar_fusion_to_detected_object Satoshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_object_clustering/CHANGELOG.rst b/perception/autoware_radar_object_clustering/CHANGELOG.rst index df38cbed59c27..b1609dd939090 100644 --- a/perception/autoware_radar_object_clustering/CHANGELOG.rst +++ b/perception/autoware_radar_object_clustering/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_radar_object_clustering ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* docs: update the list styles (`#9555 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_radar_object_clustering/package.xml b/perception/autoware_radar_object_clustering/package.xml index a4611a68f93f2..c8b5278c60292 100644 --- a/perception/autoware_radar_object_clustering/package.xml +++ b/perception/autoware_radar_object_clustering/package.xml @@ -2,7 +2,7 @@ autoware_radar_object_clustering - 0.39.0 + 0.40.0 autoware_radar_object_clustering Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_radar_object_tracker/CHANGELOG.rst b/perception/autoware_radar_object_tracker/CHANGELOG.rst index dde801b38e9aa..028737b0d4482 100644 --- a/perception/autoware_radar_object_tracker/CHANGELOG.rst +++ b/perception/autoware_radar_object_tracker/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_radar_object_tracker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_radar_object_tracker/package.xml b/perception/autoware_radar_object_tracker/package.xml index f255ab28b14b9..4868e93ba9e72 100644 --- a/perception/autoware_radar_object_tracker/package.xml +++ b/perception/autoware_radar_object_tracker/package.xml @@ -2,7 +2,7 @@ autoware_radar_object_tracker - 0.39.0 + 0.40.0 Do tracking radar object Yoshi Ri Yukihiro Saito diff --git a/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst b/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst index 3d880f603fdb6..9b60a1b24ec7a 100644 --- a/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst +++ b/perception/autoware_radar_tracks_msgs_converter/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_radar_tracks_msgs_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_radar_tracks_msgs_converter/package.xml b/perception/autoware_radar_tracks_msgs_converter/package.xml index d84b7e8473f83..5b2e1c7d6a039 100644 --- a/perception/autoware_radar_tracks_msgs_converter/package.xml +++ b/perception/autoware_radar_tracks_msgs_converter/package.xml @@ -2,7 +2,7 @@ autoware_radar_tracks_msgs_converter - 0.39.0 + 0.40.0 autoware_radar_tracks_msgs_converter Satoshi Tanaka Shunsuke Miura diff --git a/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst b/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst index 1a20766e6a72c..d61173ea1cfea 100644 --- a/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst +++ b/perception/autoware_raindrop_cluster_filter/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_raindrop_cluster_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_raindrop_cluster_filter): fix clang-diagnostic-unused-private-field (`#9496 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_raindrop_cluster_filter/package.xml b/perception/autoware_raindrop_cluster_filter/package.xml index 08200191ad58b..af3a2b1e9179f 100644 --- a/perception/autoware_raindrop_cluster_filter/package.xml +++ b/perception/autoware_raindrop_cluster_filter/package.xml @@ -2,7 +2,7 @@ autoware_raindrop_cluster_filter - 0.39.0 + 0.40.0 The ROS 2 filter cluster package Yukihiro Saito Dai Nguyen diff --git a/perception/autoware_shape_estimation/CHANGELOG.rst b/perception/autoware_shape_estimation/CHANGELOG.rst index 19630554193ec..85af9f1cf54ac 100644 --- a/perception/autoware_shape_estimation/CHANGELOG.rst +++ b/perception/autoware_shape_estimation/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_shape_estimation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* refactor: correct spelling (`#9528 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_shape_estimation/package.xml b/perception/autoware_shape_estimation/package.xml index a6a9910155120..cfc1d7e829a8a 100644 --- a/perception/autoware_shape_estimation/package.xml +++ b/perception/autoware_shape_estimation/package.xml @@ -2,7 +2,7 @@ autoware_shape_estimation - 0.39.0 + 0.40.0 This package implements a shape estimation algorithm as a ROS 2 node Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_simple_object_merger/CHANGELOG.rst b/perception/autoware_simple_object_merger/CHANGELOG.rst index 8c9ac43a8382f..d45c6a726433d 100644 --- a/perception/autoware_simple_object_merger/CHANGELOG.rst +++ b/perception/autoware_simple_object_merger/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_simple_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_simple_object_merger/package.xml b/perception/autoware_simple_object_merger/package.xml index b42544aede418..db20c03a95640 100644 --- a/perception/autoware_simple_object_merger/package.xml +++ b/perception/autoware_simple_object_merger/package.xml @@ -1,7 +1,7 @@ autoware_simple_object_merger - 0.39.0 + 0.40.0 autoware_simple_object_merger Sathshi Tanaka Shunsuke Miura diff --git a/perception/autoware_tensorrt_classifier/CHANGELOG.rst b/perception/autoware_tensorrt_classifier/CHANGELOG.rst index 1fa80f20f6cb7..88311b8ed9515 100644 --- a/perception/autoware_tensorrt_classifier/CHANGELOG.rst +++ b/perception/autoware_tensorrt_classifier/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_tensorrt_classifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_tensorrt_classifier): fix clang errors (`#9508 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_tensorrt_classifier/package.xml b/perception/autoware_tensorrt_classifier/package.xml index 4813fe48cd4fd..489f5f2596e25 100644 --- a/perception/autoware_tensorrt_classifier/package.xml +++ b/perception/autoware_tensorrt_classifier/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_classifier - 0.39.0 + 0.40.0 tensorrt classifier wrapper Dan Umeda diff --git a/perception/autoware_tensorrt_common/CHANGELOG.rst b/perception/autoware_tensorrt_common/CHANGELOG.rst index 48a26ad65a610..ab3b7187c0169 100644 --- a/perception/autoware_tensorrt_common/CHANGELOG.rst +++ b/perception/autoware_tensorrt_common/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_tensorrt_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_tensorrt_common): fix clang-diagnostic-unused-private-field (`#9493 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_tensorrt_common/package.xml b/perception/autoware_tensorrt_common/package.xml index 7e29cf87b61c3..300a7b263c063 100644 --- a/perception/autoware_tensorrt_common/package.xml +++ b/perception/autoware_tensorrt_common/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_common - 0.39.0 + 0.40.0 tensorrt utility wrapper Taichi Higashide diff --git a/perception/autoware_tensorrt_yolox/CHANGELOG.rst b/perception/autoware_tensorrt_yolox/CHANGELOG.rst index b0883dab538d5..969f1df4b5496 100644 --- a/perception/autoware_tensorrt_yolox/CHANGELOG.rst +++ b/perception/autoware_tensorrt_yolox/CHANGELOG.rst @@ -2,6 +2,36 @@ Changelog for package autoware_tensorrt_yolox ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_tensorrt_yolox): fix clang-diagnostic-inconsistent-missing-override (`#9512 `_) + fix: clang-diagnostic-inconsistent-missing-override +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_tensorrt_yolox/package.xml b/perception/autoware_tensorrt_yolox/package.xml index 1c8cd51ee935c..e04d839282fd8 100644 --- a/perception/autoware_tensorrt_yolox/package.xml +++ b/perception/autoware_tensorrt_yolox/package.xml @@ -1,7 +1,7 @@ autoware_tensorrt_yolox - 0.39.0 + 0.40.0 tensorrt library implementation for yolox Daisuke Nishimatsu diff --git a/perception/autoware_tracking_object_merger/CHANGELOG.rst b/perception/autoware_tracking_object_merger/CHANGELOG.rst index 0c6aad26b02d7..337e7028ee61f 100644 --- a/perception/autoware_tracking_object_merger/CHANGELOG.rst +++ b/perception/autoware_tracking_object_merger/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_tracking_object_merger ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(autoware_tracking_object_merger): fix clang-diagnostic-sign-conversion (`#9507 `_) + fix: clang-diagnostic-sign-conversion +* fix(autoware_tracking_object_merger): fix clang-diagnostic-sign-conversion (`#9494 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/autoware_tracking_object_merger/package.xml b/perception/autoware_tracking_object_merger/package.xml index fabe4132c96ed..2b19ee381258f 100644 --- a/perception/autoware_tracking_object_merger/package.xml +++ b/perception/autoware_tracking_object_merger/package.xml @@ -2,7 +2,7 @@ autoware_tracking_object_merger - 0.39.0 + 0.40.0 merge tracking object Yukihiro Saito Yoshi Ri diff --git a/perception/autoware_traffic_light_arbiter/CHANGELOG.rst b/perception/autoware_traffic_light_arbiter/CHANGELOG.rst index b60021ffb5503..0b3182907a8ce 100644 --- a/perception/autoware_traffic_light_arbiter/CHANGELOG.rst +++ b/perception/autoware_traffic_light_arbiter/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_traffic_light_arbiter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masato Saeki, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_traffic_light_arbiter/package.xml b/perception/autoware_traffic_light_arbiter/package.xml index 46500143ed951..03d6ad5cb6cf4 100644 --- a/perception/autoware_traffic_light_arbiter/package.xml +++ b/perception/autoware_traffic_light_arbiter/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_arbiter - 0.39.0 + 0.40.0 The autoware_traffic_light_arbiter package Kenzo Lobos-Tsunekawa Shunsuke Miura diff --git a/perception/autoware_traffic_light_classifier/CHANGELOG.rst b/perception/autoware_traffic_light_classifier/CHANGELOG.rst index 394c8b3f7aeea..db6ddb6b18f87 100644 --- a/perception/autoware_traffic_light_classifier/CHANGELOG.rst +++ b/perception/autoware_traffic_light_classifier/CHANGELOG.rst @@ -2,6 +2,39 @@ Changelog for package autoware_traffic_light_classifier ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(autoware_traffic_light_classifier): fix clang-diagnostic-delete-abstract-non-virtual-dtor (`#9497 `_) + fix: clang-diagnostic-delete-abstract-non-virtual-dtor +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Masato Saeki, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_traffic_light_classifier/package.xml b/perception/autoware_traffic_light_classifier/package.xml index 5863de6ff50fd..d83791916d4b9 100644 --- a/perception/autoware_traffic_light_classifier/package.xml +++ b/perception/autoware_traffic_light_classifier/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_classifier - 0.39.0 + 0.40.0 The autoware_traffic_light_classifier package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst b/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst index 8918f357e263b..80b1fa60f9e1f 100644 --- a/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst +++ b/perception/autoware_traffic_light_fine_detector/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_traffic_light_fine_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masato Saeki, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_traffic_light_fine_detector/package.xml b/perception/autoware_traffic_light_fine_detector/package.xml index a431f071f8150..c9db06669ea99 100644 --- a/perception/autoware_traffic_light_fine_detector/package.xml +++ b/perception/autoware_traffic_light_fine_detector/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_fine_detector - 0.39.0 + 0.40.0 The autoware_traffic_light_fine_detector package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst b/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst index 312ef582da479..60f84da7131f2 100644 --- a/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst +++ b/perception/autoware_traffic_light_map_based_detector/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_traffic_light_map_based_detector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masato Saeki, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_traffic_light_map_based_detector/package.xml b/perception/autoware_traffic_light_map_based_detector/package.xml index 6c22e091ee972..c5caca47a0c39 100644 --- a/perception/autoware_traffic_light_map_based_detector/package.xml +++ b/perception/autoware_traffic_light_map_based_detector/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_map_based_detector - 0.39.0 + 0.40.0 The autoware_traffic_light_map_based_detector package Yukihiro Saito Shunsuke Miura diff --git a/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst b/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst index 4354885dcb143..74a7fa049c486 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst +++ b/perception/autoware_traffic_light_multi_camera_fusion/CHANGELOG.rst @@ -2,6 +2,41 @@ Changelog for package autoware_traffic_light_multi_camera_fusion ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(autoware_traffic_light_multi_camera_fusion): resolve clang-tidy error (`#9336 `_) + * feat(autoware_traffic_light_multi_camera_fusion): resolve clang-tidy error + * add const to argument + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masato Saeki, Ryohsuke Mitsudome, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_traffic_light_multi_camera_fusion/package.xml b/perception/autoware_traffic_light_multi_camera_fusion/package.xml index efa8571a660a8..dfe8657577582 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/package.xml +++ b/perception/autoware_traffic_light_multi_camera_fusion/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_multi_camera_fusion - 0.39.0 + 0.40.0 The autoware_traffic_light_multi_camera_fusion package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst b/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst index fb31d9ffdf0c1..8dec833763cb7 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst +++ b/perception/autoware_traffic_light_occlusion_predictor/CHANGELOG.rst @@ -2,6 +2,38 @@ Changelog for package autoware_traffic_light_occlusion_predictor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(traffic_light_utils): prefix package and namespace with autoware (`#9251 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masato Saeki, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_traffic_light_occlusion_predictor/package.xml b/perception/autoware_traffic_light_occlusion_predictor/package.xml index b1dbc773b5eb0..e10dddaf40eaf 100644 --- a/perception/autoware_traffic_light_occlusion_predictor/package.xml +++ b/perception/autoware_traffic_light_occlusion_predictor/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_occlusion_predictor - 0.39.0 + 0.40.0 The autoware_traffic_light_occlusion_predictor package Tao Zhong Shunsuke Miura diff --git a/perception/autoware_traffic_light_visualization/CHANGELOG.rst b/perception/autoware_traffic_light_visualization/CHANGELOG.rst index 7da332f0f878b..420b4bf485eec 100644 --- a/perception/autoware_traffic_light_visualization/CHANGELOG.rst +++ b/perception/autoware_traffic_light_visualization/CHANGELOG.rst @@ -2,6 +2,40 @@ Changelog for package autoware_traffic_light_visualization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* fix(traffic_light_roi_visualizer): show unknown results correctly (`#9467 `_) + fix: show unknown results correctly +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light_visualization): include opencv as system (`#9331 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_traffic_light*): add maintainer (`#9280 `_) + * add fundamental commit + * add forgot package + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masato Saeki, Ryohsuke Mitsudome, Tao Zhong, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/perception/autoware_traffic_light_visualization/package.xml b/perception/autoware_traffic_light_visualization/package.xml index 210700799ea73..afb30d43f2a70 100644 --- a/perception/autoware_traffic_light_visualization/package.xml +++ b/perception/autoware_traffic_light_visualization/package.xml @@ -2,7 +2,7 @@ autoware_traffic_light_visualization - 0.39.0 + 0.40.0 The autoware_traffic_light_visualization package Yukihiro Saito Tao Zhong diff --git a/perception/perception_utils/CHANGELOG.rst b/perception/perception_utils/CHANGELOG.rst index 2dbb57cbd2f48..ddbe6e3f40270 100644 --- a/perception/perception_utils/CHANGELOG.rst +++ b/perception/perception_utils/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package perception_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - perception (`#9569 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(perception_utils): install include directory (`#9354 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/perception/perception_utils/package.xml b/perception/perception_utils/package.xml index 7001d249e1f52..058811b048459 100644 --- a/perception/perception_utils/package.xml +++ b/perception/perception_utils/package.xml @@ -2,7 +2,7 @@ perception_utils - 0.39.0 + 0.40.0 The perception_utils package Shunsuke Miura Yoshi Ri diff --git a/planning/autoware_costmap_generator/CHANGELOG.rst b/planning/autoware_costmap_generator/CHANGELOG.rst index 2dad489bbc6a4..6215cd6361b49 100644 --- a/planning/autoware_costmap_generator/CHANGELOG.rst +++ b/planning/autoware_costmap_generator/CHANGELOG.rst @@ -2,6 +2,57 @@ Changelog for package autoware_costmap_generator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat(costmap_generator, scenario_selector): improve freespace planning stability (`#9579 `_) + * discretize updating grid center position by size of grid resolution + * modify logic for switching to lane driving in scenario selector + * fix spelling + --------- +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor: correct spelling (`#9528 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_costmap_generator): fix clang-diagnostic-unused-private-field (`#9395 `_) + fix: clang-diagnostic-unused-private-field +* fix(costmap_generator): use vehicle frame for lidar height thresholds (`#9311 `_) +* test(costmap_generator): unit test implementation for costmap generator (`#9149 `_) + * modify costmap generator directory structure + * rename class CostmapGenerator to CostmapGeneratorNode + * unit test for object_map_utils + * catch error from lookupTransform + * use polling subscriber in costmap generator node + * add test for costmap generator node + * add test for isActive() + * revert unnecessary changes + * remove commented out line + * minor fix + * Update planning/autoware_costmap_generator/src/costmap_generator.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Maxime CLEMENT, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858, mkquda + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/autoware_costmap_generator/package.xml b/planning/autoware_costmap_generator/package.xml index d3b03f171ef97..9097109de0a0b 100644 --- a/planning/autoware_costmap_generator/package.xml +++ b/planning/autoware_costmap_generator/package.xml @@ -2,7 +2,7 @@ autoware_costmap_generator - 0.39.0 + 0.40.0 The autoware_costmap_generator package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst b/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst index 544a12e7cde26..0dd0f835c1f53 100644 --- a/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst +++ b/planning/autoware_external_velocity_limit_selector/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_external_velocity_limit_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat(velocity_smoother, external_velocity_limit_selector): enable stronger acceleration when requested (`#9502 `_) + * change max acceleration and max jerk according to external velocity request + * modify external velocity limit selector + * fix external velocity limit selector + * fix format + --------- +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_external_velocity_limit_selector/package.xml b/planning/autoware_external_velocity_limit_selector/package.xml index 4779de30519a0..b75a4fab72d7c 100644 --- a/planning/autoware_external_velocity_limit_selector/package.xml +++ b/planning/autoware_external_velocity_limit_selector/package.xml @@ -2,7 +2,7 @@ autoware_external_velocity_limit_selector - 0.39.0 + 0.40.0 The autoware_external_velocity_limit_selector ROS 2 package Satoshi Ota Shinnosuke Hirakawa diff --git a/planning/autoware_freespace_planner/CHANGELOG.rst b/planning/autoware_freespace_planner/CHANGELOG.rst index 277d7f96d5d15..ad8960a64d3d2 100644 --- a/planning/autoware_freespace_planner/CHANGELOG.rst +++ b/planning/autoware_freespace_planner/CHANGELOG.rst @@ -2,6 +2,47 @@ Changelog for package autoware_freespace_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* fix(autoware_freespace_planner, autoware_freespace_planning_algorithms): modify freespace planner to use node clock instead of system clock (`#9152 `_) + * Modified the autoware_freespace_planner and autoware_freespace_planning_algorithms packages to use the node clock instead of rclcpp detached clock. This allows the module to make use of sim time. Previously during simulation the parking trajectory would have system time in trajectory header messages causing downstream issues like non-clearance of trajectory buffers in motion planning based on elapsed time. + * style(pre-commit): autofix + * Updated the freespace planner instantiation call in the path planning modules + * style(pre-commit): autofix + * Updated tests for the utility functions + * style(pre-commit): autofix + --------- + Co-authored-by: Steven Brills + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(freespace_planner): add processing time pub (`#9332 `_) +* fix(freespace_planner): fix is near target check (`#9327 `_) + * fix is_near_target_check + * update unit test + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kazunori-Nakajima, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, mkquda, stevenbrills + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_freespace_planner/package.xml b/planning/autoware_freespace_planner/package.xml index 84818e70f220a..fd7e39d191647 100644 --- a/planning/autoware_freespace_planner/package.xml +++ b/planning/autoware_freespace_planner/package.xml @@ -2,7 +2,7 @@ autoware_freespace_planner - 0.39.0 + 0.40.0 The autoware_freespace_planner package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst b/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst index c032ebe44f723..8f6b94a2e0a80 100644 --- a/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst +++ b/planning/autoware_freespace_planning_algorithms/CHANGELOG.rst @@ -2,6 +2,54 @@ Changelog for package autoware_freespace_planning_algorithms ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor: correct spelling (`#9528 `_) +* fix(autoware_freespace_planner, autoware_freespace_planning_algorithms): modify freespace planner to use node clock instead of system clock (`#9152 `_) + * Modified the autoware_freespace_planner and autoware_freespace_planning_algorithms packages to use the node clock instead of rclcpp detached clock. This allows the module to make use of sim time. Previously during simulation the parking trajectory would have system time in trajectory header messages causing downstream issues like non-clearance of trajectory buffers in motion planning based on elapsed time. + * style(pre-commit): autofix + * Updated the freespace planner instantiation call in the path planning modules + * style(pre-commit): autofix + * Updated tests for the utility functions + * style(pre-commit): autofix + --------- + Co-authored-by: Steven Brills + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(autoware_freespace_planning_algorithms): fix clang-diagnostic-unused-const-variable (`#9433 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_freespace_planning_algorithms): fix clang-diagnostic-ignored-optimization-argument (`#9418 `_) + fix: clang-diagnostic-ignored-optimization-argument +* fix(autoware_freespace_planning_algorithms): fix clang-diagnostic-unused-private-field (`#9396 `_) + * fix: clang-diagnostic-unused-private-field + * fix: build error + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(/autoware_freespace_planning_algorithms): fix cppcheck unusedFunction (`#9274 `_) +* fix(autoware_freespace_planning_algorithms): fix bugprone-unused-raii (`#9230 `_) + fix: bugprone-unused-raii +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo, kobayu858, stevenbrills + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/autoware_freespace_planning_algorithms/package.xml b/planning/autoware_freespace_planning_algorithms/package.xml index 9a9b7ad0c586f..4bffa7bd15c1d 100644 --- a/planning/autoware_freespace_planning_algorithms/package.xml +++ b/planning/autoware_freespace_planning_algorithms/package.xml @@ -2,7 +2,7 @@ autoware_freespace_planning_algorithms - 0.39.0 + 0.40.0 The autoware_freespace_planning_algorithms package Kosuke Takeuchi Takamasa Horibe diff --git a/planning/autoware_mission_planner/CHANGELOG.rst b/planning/autoware_mission_planner/CHANGELOG.rst index bdab400dfa983..ed21313c96af2 100644 --- a/planning/autoware_mission_planner/CHANGELOG.rst +++ b/planning/autoware_mission_planner/CHANGELOG.rst @@ -2,6 +2,49 @@ Changelog for package autoware_mission_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix: autoware_glog_compontnt (`#9586 `_) + Fixed autoware_glog_compontnt +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor(glog_component): prefix package and namespace with autoware (`#9302 `_) + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> +* fix(mission_planner): fix initialization after route set (`#9457 `_) +* fix(autoware_mission_planner): fix clang-diagnostic-error (`#9432 `_) +* feat(mission_planner): add processing time publisher (`#9342 `_) + * feat(mission_planner): add processing time publisher + * delete extra line + * update: mission_planner, route_selector, service_utils. + * Revert "update: mission_planner, route_selector, service_utils." + This reverts commit d460a633c04c166385963c5233c3845c661e595e. + * Update to show that exceptions are not handled + * feat(mission_planner,route_selector): add processing time publisher + --------- + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> + Co-authored-by: Kosuke Takeuchi +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kazunori-Nakajima, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, SakodaShintaro, Takagi, Isamu, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_mission_planner/package.xml b/planning/autoware_mission_planner/package.xml index d249d2fb00021..e7cf974b2ba25 100644 --- a/planning/autoware_mission_planner/package.xml +++ b/planning/autoware_mission_planner/package.xml @@ -2,7 +2,7 @@ autoware_mission_planner - 0.39.0 + 0.40.0 The autoware_mission_planner package Takagi, Isamu Kosuke Takeuchi diff --git a/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst b/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst index 891d36e2a3be5..16b583990ec3e 100644 --- a/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst +++ b/planning/autoware_objects_of_interest_marker_interface/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_objects_of_interest_marker_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_objects_of_interest_marker_interface/package.xml b/planning/autoware_objects_of_interest_marker_interface/package.xml index 15f2adac6924d..6d179f7872dc1 100644 --- a/planning/autoware_objects_of_interest_marker_interface/package.xml +++ b/planning/autoware_objects_of_interest_marker_interface/package.xml @@ -1,7 +1,7 @@ autoware_objects_of_interest_marker_interface - 0.39.0 + 0.40.0 The autoware_objects_of_interest_marker_interface package Fumiya Watanabe diff --git a/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst b/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst index 8b0192c171a29..827fee6a58039 100644 --- a/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst +++ b/planning/autoware_obstacle_cruise_planner/CHANGELOG.rst @@ -2,6 +2,70 @@ Changelog for package autoware_obstacle_cruise_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* refactor(obstacle_cruise_planner)!: refactor rviz and terminal info (`#9594 `_) +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* fix(obstacle_cruise_planner)!: remove stop reason (`#9464 `_) + fix(obstacle_cruise_planner): remove stop reason +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(obstacle_cruise_planner): outputs velocity factor when the ego follows front vehicle. (`#9359 `_) + * feat(obstacle_cruise_planner): outputs velocity factor when the ego follows front vehicle. + * fix: cppcheck + --------- +* fix(autoware_obstacle_cruise_planner): fix clang-diagnostic-delete-abstract-non-virtual-dtor (`#9419 `_) + fix: clang-diagnostic-delete-abstract-non-virtual-dtor +* fix(autoware_obstacle_cruise_planner): fix clang-diagnostic-defaulted-function-deleted (`#9398 `_) + fix: clang-diagnostic-defaulted-function-deleted +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* chore(obstacle_cruise_planner): add function tests for a utils function (`#9206 `_) + * add utils test + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yuki TAKAGI, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/autoware_obstacle_cruise_planner/package.xml b/planning/autoware_obstacle_cruise_planner/package.xml index 75405c3aded2a..8583d0639e5ce 100644 --- a/planning/autoware_obstacle_cruise_planner/package.xml +++ b/planning/autoware_obstacle_cruise_planner/package.xml @@ -1,7 +1,7 @@ autoware_obstacle_cruise_planner - 0.39.0 + 0.40.0 The autoware_obstacle_cruise_planner package Takayuki Murooka diff --git a/planning/autoware_obstacle_stop_planner/CHANGELOG.rst b/planning/autoware_obstacle_stop_planner/CHANGELOG.rst index 2afc9c79edac5..867553c9ffd4e 100644 --- a/planning/autoware_obstacle_stop_planner/CHANGELOG.rst +++ b/planning/autoware_obstacle_stop_planner/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_obstacle_stop_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* fix(obstacle_stop_planner): remove stop reason (`#9465 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_obstacle_stop_planner): fix cppcheck warnings (`#9388 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Satoshi OTA, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_obstacle_stop_planner/package.xml b/planning/autoware_obstacle_stop_planner/package.xml index d46ad5c6c2a0d..c9c78b3e87c3b 100644 --- a/planning/autoware_obstacle_stop_planner/package.xml +++ b/planning/autoware_obstacle_stop_planner/package.xml @@ -2,7 +2,7 @@ autoware_obstacle_stop_planner - 0.39.0 + 0.40.0 The autoware_obstacle_stop_planner package Satoshi Ota diff --git a/planning/autoware_path_optimizer/CHANGELOG.rst b/planning/autoware_path_optimizer/CHANGELOG.rst index 07ea508e53c07..19798e6697ec6 100644 --- a/planning/autoware_path_optimizer/CHANGELOG.rst +++ b/planning/autoware_path_optimizer/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_path_optimizer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor(global_parameter_loader): prefix package and namespace with autoware (`#9303 `_) +* docs: update the list styles (`#9555 `_) +* fix(path_optimizer): solve issue with time keeper (`#9483 `_) + solve issue with time keeper +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(fake_test_node): prefix package and namespace with autoware (`#9249 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, danielsanchezaran + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_path_optimizer/package.xml b/planning/autoware_path_optimizer/package.xml index 8ab7d50ccada4..eb02db8ea9586 100644 --- a/planning/autoware_path_optimizer/package.xml +++ b/planning/autoware_path_optimizer/package.xml @@ -2,7 +2,7 @@ autoware_path_optimizer - 0.39.0 + 0.40.0 The autoware_path_optimizer package Takayuki Murooka Kosuke Takeuchi diff --git a/planning/autoware_path_smoother/CHANGELOG.rst b/planning/autoware_path_smoother/CHANGELOG.rst index 823219e9dd303..4b7f86361c63b 100644 --- a/planning/autoware_path_smoother/CHANGELOG.rst +++ b/planning/autoware_path_smoother/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_path_smoother ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor: correct spelling (`#9528 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(fake_test_node): prefix package and namespace with autoware (`#9249 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_path_smoother/package.xml b/planning/autoware_path_smoother/package.xml index 572cf514b7be5..3fa7b9fa482ed 100644 --- a/planning/autoware_path_smoother/package.xml +++ b/planning/autoware_path_smoother/package.xml @@ -2,7 +2,7 @@ autoware_path_smoother - 0.39.0 + 0.40.0 The autoware_path_smoother package Takayuki Murooka Maxime CLEMENT diff --git a/planning/autoware_planning_test_manager/CHANGELOG.rst b/planning/autoware_planning_test_manager/CHANGELOG.rst index 3d674c64296af..f1ac0f088c3cc 100644 --- a/planning/autoware_planning_test_manager/CHANGELOG.rst +++ b/planning/autoware_planning_test_manager/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_planning_test_manager ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(planning_test_manager): update owner (`#9620 `_) +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor(test_utils): return parser as optional (`#9391 `_) + Co-authored-by: Mamoru Sobue +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yutaka Kondo, Zulfaqar Azmi + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/autoware_planning_test_manager/package.xml b/planning/autoware_planning_test_manager/package.xml index 1b38944f545bc..80801a8102453 100644 --- a/planning/autoware_planning_test_manager/package.xml +++ b/planning/autoware_planning_test_manager/package.xml @@ -2,7 +2,7 @@ autoware_planning_test_manager - 0.39.0 + 0.40.0 ROS 2 node for testing interface of the nodes in planning module Kyoichi Sugahara Takamasa Horibe diff --git a/planning/autoware_planning_topic_converter/CHANGELOG.rst b/planning/autoware_planning_topic_converter/CHANGELOG.rst index 897a99d1e0bc2..e937e664654a2 100644 --- a/planning/autoware_planning_topic_converter/CHANGELOG.rst +++ b/planning/autoware_planning_topic_converter/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_planning_topic_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_planning_topic_converter/package.xml b/planning/autoware_planning_topic_converter/package.xml index 3503a9bebda40..e2585924a61d2 100644 --- a/planning/autoware_planning_topic_converter/package.xml +++ b/planning/autoware_planning_topic_converter/package.xml @@ -1,7 +1,7 @@ autoware_planning_topic_converter - 0.39.0 + 0.40.0 The autoware_planning_topic_converter package Satoshi OTA diff --git a/planning/autoware_planning_validator/CHANGELOG.rst b/planning/autoware_planning_validator/CHANGELOG.rst index 9828da69cf80d..76018e5bf5f11 100644 --- a/planning/autoware_planning_validator/CHANGELOG.rst +++ b/planning/autoware_planning_validator/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_planning_validator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_planning_validator/package.xml b/planning/autoware_planning_validator/package.xml index 9db00b580b60d..1652c2ad4f544 100644 --- a/planning/autoware_planning_validator/package.xml +++ b/planning/autoware_planning_validator/package.xml @@ -2,7 +2,7 @@ autoware_planning_validator - 0.39.0 + 0.40.0 ros node for autoware_planning_validator Takamasa Horibe Kosuke Takeuchi diff --git a/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst b/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst index 7a8d11d37fe1e..570e7b4783ca4 100644 --- a/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst +++ b/planning/autoware_remaining_distance_time_calculator/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_remaining_distance_time_calculator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml index 55033af92656b..924e6d62d6aba 100644 --- a/planning/autoware_remaining_distance_time_calculator/package.xml +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -1,7 +1,7 @@ autoware_remaining_distance_time_calculator - 0.39.0 + 0.40.0 Calculates and publishes remaining distance and time of the mission. Ahmed Ebrahim diff --git a/planning/autoware_route_handler/CHANGELOG.rst b/planning/autoware_route_handler/CHANGELOG.rst index 37c1db12186ce..d70e5897c96b5 100644 --- a/planning/autoware_route_handler/CHANGELOG.rst +++ b/planning/autoware_route_handler/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_route_handler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor(test_utils): return parser as optional (`#9391 `_) + Co-authored-by: Mamoru Sobue +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, Zulfaqar Azmi + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_route_handler/package.xml b/planning/autoware_route_handler/package.xml index 78a024a8c5f82..ededbcc9eef3d 100644 --- a/planning/autoware_route_handler/package.xml +++ b/planning/autoware_route_handler/package.xml @@ -2,7 +2,7 @@ autoware_route_handler - 0.39.0 + 0.40.0 The route_handling package Fumiya Watanabe Zulfaqar Azmi diff --git a/planning/autoware_rtc_interface/CHANGELOG.rst b/planning/autoware_rtc_interface/CHANGELOG.rst index 3c6fe2604d2ab..11672d2c47e3e 100644 --- a/planning/autoware_rtc_interface/CHANGELOG.rst +++ b/planning/autoware_rtc_interface/CHANGELOG.rst @@ -2,6 +2,44 @@ Changelog for package autoware_rtc_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_rtc_interface): fix dependency (`#9237 `_) +* fix(rtc_interface): update requested field for every cooperateStatus state (`#9211 `_) + * fix rtc_interface + * fix test condition + --------- +* feat(rtc_interface): add requested field (`#9202 `_) + * add requested feature + * Update planning/autoware_rtc_interface/test/test_rtc_interface.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> +* Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/autoware_rtc_interface/package.xml b/planning/autoware_rtc_interface/package.xml index 668e31093072e..861554e81408e 100644 --- a/planning/autoware_rtc_interface/package.xml +++ b/planning/autoware_rtc_interface/package.xml @@ -1,7 +1,7 @@ autoware_rtc_interface - 0.39.0 + 0.40.0 The autoware_rtc_interface package Fumiya Watanabe diff --git a/planning/autoware_scenario_selector/CHANGELOG.rst b/planning/autoware_scenario_selector/CHANGELOG.rst index 0e1a560fa95e8..877192f0e68f9 100644 --- a/planning/autoware_scenario_selector/CHANGELOG.rst +++ b/planning/autoware_scenario_selector/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_scenario_selector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat(costmap_generator, scenario_selector): improve freespace planning stability (`#9579 `_) + * discretize updating grid center position by size of grid resolution + * modify logic for switching to lane driving in scenario selector + * fix spelling + --------- +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, mkquda + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_scenario_selector/package.xml b/planning/autoware_scenario_selector/package.xml index 9787f95ed9fde..e726e40acecce 100644 --- a/planning/autoware_scenario_selector/package.xml +++ b/planning/autoware_scenario_selector/package.xml @@ -2,7 +2,7 @@ autoware_scenario_selector - 0.39.0 + 0.40.0 The autoware_scenario_selector ROS 2 package Taiki Tanaka Tomoya Kimura diff --git a/planning/autoware_static_centerline_generator/CHANGELOG.rst b/planning/autoware_static_centerline_generator/CHANGELOG.rst index 6fac2e4677528..0338cdc8b66bb 100644 --- a/planning/autoware_static_centerline_generator/CHANGELOG.rst +++ b/planning/autoware_static_centerline_generator/CHANGELOG.rst @@ -2,6 +2,61 @@ Changelog for package autoware_static_centerline_generator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix(static_centerline_generator): several bug fixes (`#9426 `_) + * fix: dependent packages + * feat: use steer angle, use warn for steer angle failure, calc curvature dicontinuously + * fix cppcheck + --------- +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor(global_parameter_loader): prefix package and namespace with autoware (`#9303 `_) +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(static_centerline_generator): map_tf_generator package name needs update (`#9383 `_) + fix map_tf_generator name in autoware_static_centerline_generator.launch +* refactor(map_loader)!: prefix package and namespace with autoware (`#8927 `_) + * make lanelet2_map_visualization independent + * remove unused files + * remove unused package + * fix package name + * add autoware\_ prefix + * add autoware to exec name + * add autoware prefix + * removed unnecessary dependency + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Masaki Baba, Ryohsuke Mitsudome, Takayuki Murooka, Yutaka Kondo, Zhanhong Yan + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_static_centerline_generator/package.xml b/planning/autoware_static_centerline_generator/package.xml index 6ba1494e714cd..cea18e5605921 100644 --- a/planning/autoware_static_centerline_generator/package.xml +++ b/planning/autoware_static_centerline_generator/package.xml @@ -2,7 +2,7 @@ autoware_static_centerline_generator - 0.39.0 + 0.40.0 The autoware_static_centerline_generator package Takayuki Murooka Kosuke Takeuchi diff --git a/planning/autoware_surround_obstacle_checker/CHANGELOG.rst b/planning/autoware_surround_obstacle_checker/CHANGELOG.rst index 077b52e08e342..c6e1a13a59aa2 100644 --- a/planning/autoware_surround_obstacle_checker/CHANGELOG.rst +++ b/planning/autoware_surround_obstacle_checker/CHANGELOG.rst @@ -2,6 +2,43 @@ Changelog for package autoware_surround_obstacle_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* ci(pre-commit): autoupdate (`#8949 `_) + Co-authored-by: M. Fatih Cırıt +* fix(surround_obstacle_checker)!: remove stop reason (`#9450 `_) + fix(surround_obstacle_checker): remove stop reason +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_surround_obstacle_checker): fix clang-diagnostic-unused-private-field (`#9399 `_) + * fix: clang-diagnostic-unused-private-field + * refactor: fmt + * refactor: fmt + * refactor: fmt + * fix: hpp + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo, awf-autoware-bot[bot], kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/autoware_surround_obstacle_checker/package.xml b/planning/autoware_surround_obstacle_checker/package.xml index 64a626c0ccb60..4a6f946b8eb90 100644 --- a/planning/autoware_surround_obstacle_checker/package.xml +++ b/planning/autoware_surround_obstacle_checker/package.xml @@ -2,7 +2,7 @@ autoware_surround_obstacle_checker - 0.39.0 + 0.40.0 The autoware_surround_obstacle_checker package Satoshi Ota Go Sakayori diff --git a/planning/autoware_velocity_smoother/CHANGELOG.rst b/planning/autoware_velocity_smoother/CHANGELOG.rst index 14c905b82cfa1..4655c9658ef2b 100644 --- a/planning/autoware_velocity_smoother/CHANGELOG.rst +++ b/planning/autoware_velocity_smoother/CHANGELOG.rst @@ -2,6 +2,40 @@ Changelog for package autoware_velocity_smoother ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(velocity_smoother, external_velocity_limit_selector): enable stronger acceleration when requested (`#9502 `_) + * change max acceleration and max jerk according to external velocity request + * modify external velocity limit selector + * fix external velocity limit selector + * fix format + --------- +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(qp_interface): prefix package and namespace with autoware (`#9236 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/autoware_velocity_smoother/package.xml b/planning/autoware_velocity_smoother/package.xml index c27a984c36681..96462602d8da0 100644 --- a/planning/autoware_velocity_smoother/package.xml +++ b/planning/autoware_velocity_smoother/package.xml @@ -2,7 +2,7 @@ autoware_velocity_smoother - 0.39.0 + 0.40.0 The autoware_velocity_smoother package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst index e736da5b9fb49..0b2d004e1f02b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/CHANGELOG.rst @@ -2,6 +2,43 @@ Changelog for package autoware_behavior_path_avoidance_by_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml index 43195e8ca502b..83c361d064fb0 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_avoidance_by_lane_change_module - 0.39.0 + 0.40.0 The behavior_path_avoidance_by_lane_change_module package Satoshi Ota diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst index 7219f13994710..5b5179f250d8d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/CHANGELOG.rst @@ -2,6 +2,43 @@ Changelog for package autoware_behavior_path_dynamic_obstacle_avoidance_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml index 1829d9a949115..e3aefb01c797d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_dynamic_obstacle_avoidance_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_dynamic_obstacle_avoidance_module - 0.39.0 + 0.40.0 The autoware_behavior_path_dynamic_obstacle_avoidance_module package Takayuki Murooka diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst index cdd6bc1033d7e..0a315105e5bf1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/CHANGELOG.rst @@ -2,6 +2,43 @@ Changelog for package autoware_behavior_path_external_request_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml index 981f119357ca0..af46393d9b9ae 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_external_request_lane_change_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_external_request_lane_change_module - 0.39.0 + 0.40.0 The autoware_behavior_path_external_request_lane_change_module package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst index 1813e0ac901f9..627f216b6d7c9 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/CHANGELOG.rst @@ -2,6 +2,88 @@ Changelog for package autoware_behavior_path_goal_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* feat(behavior_path_planner): add detail text to virutal wall (`#9600 `_) + * feat(behavior_path_planner): add detail text to virutal wall + * goal is far + * pull over start pose is far + * fix lc build + * fix build + * Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp + --------- +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(goal_planner): fix isStopped judgement (`#9585 `_) + * fix(goal_planner): fix isStopped judgement + * fix typo + --------- +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat(goal_planner): check opposite lane for lane departure_check (`#9460 `_) + * feat(goal_planner): check opposite lane for lane departure_check + * refactor getMostInnerLane + --------- +* refactor(goal_planner): improve log message and change level (`#9562 `_) + Co-authored-by: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor(goal_planner): move PathDecisionController implementation to a different file (`#9523 `_) + refactor(goal_planner): move decision_state implementation +* refactor(goal_planner): move unnecessary member functions (`#9522 `_) +* fix(autoware_freespace_planner, autoware_freespace_planning_algorithms): modify freespace planner to use node clock instead of system clock (`#9152 `_) + * Modified the autoware_freespace_planner and autoware_freespace_planning_algorithms packages to use the node clock instead of rclcpp detached clock. This allows the module to make use of sim time. Previously during simulation the parking trajectory would have system time in trajectory header messages causing downstream issues like non-clearance of trajectory buffers in motion planning based on elapsed time. + * style(pre-commit): autofix + * Updated the freespace planner instantiation call in the path planning modules + * style(pre-commit): autofix + * Updated tests for the utility functions + * style(pre-commit): autofix + --------- + Co-authored-by: Steven Brills + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(goal_planner): fix multiple lane ids of shift pull over (`#9360 `_) + fix vel +* fix(goal_planner): remove stop reason (`#9365 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(goal_planner): use departure_check_lane for path (`#9423 `_) +* refactor(goal_planner): rename shoulder_lane to pull_over_lane (`#9422 `_) +* feat(goal_planner): do not insert shift end pose on pull over lane to path (`#9361 `_) +* feat(goal_planner): remove unnecessary member from ThreadSafeData (`#9393 `_) +* feat(goal_planner): move goal_candidates from ThreadSafeData to GoalPlannerData (`#9292 `_) +* feat(goal_planner): output velocity factor (`#9348 `_) +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* refactor(goal_planner): remove reference_goal_pose getter/setter (`#9270 `_) +* feat(goal_planner): safety check with only parking path (`#9293 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(goal_planner): sort candidate path only when num to avoid is different (`#9271 `_) +* fix(autoware_behavior_path_goal_planner_module): fix cppcheck unreadVariable (`#9192 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Ryuta Kambe, Satoshi OTA, Yutaka Kondo, stevenbrills + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml index dc7221d0fd604..dead1e4fe0f37 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_goal_planner_module - 0.39.0 + 0.40.0 The autoware_behavior_path_goal_planner_module package Kosuke Takeuchi diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst index 572a09aeda817..42f6ddf841fec 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/CHANGELOG.rst @@ -2,6 +2,292 @@ Changelog for package autoware_behavior_path_lane_change_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* feat(behavior_path_planner): add detail text to virutal wall (`#9600 `_) + * feat(behavior_path_planner): add detail text to virutal wall + * goal is far + * pull over start pose is far + * fix lc build + * fix build + * Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp + --------- +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(lane_change): check obj predicted path when filtering (`#9385 `_) + * RT1-8537 check object's predicted path when filtering + * use ranges view in get_line_string_paths + * check only vehicle type predicted path + * Refactor naming + * fix grammatical + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * precommit and grammar fix + --------- + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat(lane_change): reduce prepare duration when blinker has been activated (`#9185 `_) + * add minimum prepare duration parameter + * reduce prepare duration according to signal activation time + * chore: update CODEOWNERS (`#9203 `_) + Co-authored-by: github-actions + * refactor(time_utils): prefix package and namespace with autoware (`#9173 `_) + * refactor(time_utils): prefix package and namespace with autoware + * refactor(time_utils): prefix package and namespace with autoware + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * feat(rtc_interface): add requested field (`#9202 `_) + * add requested feature + * Update planning/autoware_rtc_interface/test/test_rtc_interface.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + * fix(mpc_lateral_controller): correctly resample the MPC trajectory yaws (`#9199 `_) + * fix(bpp): prevent accessing nullopt (`#9204 `_) + fix(bpp): calcDistanceToRedTrafficLight null + * refactor(autoware_map_based_prediction): split pedestrian and bicycle predictor (`#9201 `_) + * refactor: grouping functions + * refactor: grouping parameters + * refactor: rename member road_users_history to road_users_history\_ + * refactor: separate util functions + * refactor: Add predictor_vru.cpp and utils.cpp to map_based_prediction_node + * refactor: Add explicit template instantiation for removeOldObjectsHistory function + * refactor: Add tf2_geometry_msgs to data_structure + * refactor: Remove unused variables and functions in map_based_prediction_node.cpp + * Update perception/autoware_map_based_prediction/include/map_based_prediction/predictor_vru.hpp + * Apply suggestions from code review + * style(pre-commit): autofix + --------- + Co-authored-by: Mamoru Sobue + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (`#8912 `_) + * Moved ndt_omp into ndt_scan_matcher + * Added Copyright + * style(pre-commit): autofix + * Fixed include + * Fixed cast style + * Fixed include + * Fixed honorific title + * Fixed honorific title + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed include hierarchy + * style(pre-commit): autofix + * Fixed hierarchy + * Fixed NVTP to NVTL + * Added cspell:ignore + * Fixed miss spell + * style(pre-commit): autofix + * Fixed include + * Renamed applyFilter + * Moved ***_impl.hpp from include/ to src/ + * style(pre-commit): autofix + * Fixed variable scope + * Fixed to pass by reference + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + * feat(autoware_test_utils): add traffic light msgs parser (`#9177 `_) + * modify implementation to compute and keep actual prepare duration in transient data + * if LC path is approved, set prepare duration in transient data from approved path prepare duration + * change default value of LC param min_prepare_duration + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * add function to set signal activation time, add docstring for function calc_actual_prepare_duration + * check for zero value max_acc to avoid division by zero + * chore: rename codeowners file + * chore: rename codeowners file + * chore: rename codeowners file + * allow decelerating in lane changing phase near terminal + * fix spelling + * fix units + * allow decelerating in lane changing phase near terminal + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * run pre-commit check + * fix spelling + * fix format + * allow decelerating in lane changing phase near terminal + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * run pre-commit check + * fix spelling + * fix format + --------- + Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]@users.noreply.github.com> + Co-authored-by: github-actions + Co-authored-by: Esteve Fernandez <33620+esteve@users.noreply.github.com> + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Go Sakayori + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> + Co-authored-by: Taekjin LEE + Co-authored-by: Mamoru Sobue + Co-authored-by: SakodaShintaro + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + Co-authored-by: tomoya.kimura +* feat(lane_changing): improve computation of lane changing acceleration (`#9545 `_) + * allow decelerating in lane changing phase near terminal + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * run pre-commit check + * fix spelling + * fix format + --------- + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor(test_utils): return parser as optional (`#9391 `_) + Co-authored-by: Mamoru Sobue +* fix(lane_change): cap ego's predicted path velocity (RT1-8505) (`#9341 `_) + * fix(lane_change): cap ego's predicted path velocity (RT1-8505) + * properly cap based on 0.0 instead of min lc vel + * fix build error + --------- +* fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-unused-variable (`#9401 `_) +* feat(lane_change): improve delay lane change logic (`#9480 `_) + * implement function to check if lane change delay is required + * refactor function isParkedObject + * refactor delay lane change parameters + * update lc param yaml + * separate target lane leading objects based on behavior (RT1-8532) + * fixed overlapped filtering and lanes debug marker + * combine filteredObjects function + * renaming functions and type + * update some logic to check is stopped + * rename expanded to stopped_outside_boundary + * Include docstring + * rename stopped_outside_boundary → stopped_at_bound + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * spell-check + * add docstring for function is_delay_lane_change + * remove unused functions + * fix spelling + * add delay parameters to README + * add documentation for delay lane change behavior + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * run pre-commit checks + * only check for delay lc if feature is enabled + --------- + Co-authored-by: Zulfaqar Azmi + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> +* fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-error (`#9402 `_) +* fix(autoware_behavior_path_lane_change_module): fix clang-diagnostic-overloaded-virtual (`#9400 `_) +* feat(lane_change): parse predicted objects for lane change test (RT1-8251) (`#9256 `_) + * RT1-8251 parse predicted objects + * fix pre-commit and build error + * add additional test and fix test failure + * fix lint_cmake failure + * use expect instead + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/test/test_lane_change_scene.cpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* refactor(lane_change): refactor lane change parameters (`#9403 `_) + * refactor lane change parameters + * update lane change param yaml + * update lane change README + * regroup some parameters + * run pre-commit prettier step + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/parameters.hpp + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/README.md + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + * apply pre-commit checks + --------- + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(lane_change): separate target lane leading based on obj behavior (`#9372 `_) + * separate target lane leading objects based on behavior (RT1-8532) + * fixed overlapped filtering and lanes debug marker + * combine filteredObjects function + * renaming functions and type + * update some logic to check is stopped + * rename expanded to stopped_outside_boundary + * Include docstring + * rename stopped_outside_boundary → stopped_at_bound + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * spell-check + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* feat(lane_change): output velocity factor (`#9349 `_) +* refactor(lane_change): refactor extended object safety check (`#9322 `_) + * refactor LC extended object collision check code + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> + --------- + Co-authored-by: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(lane_change): remove std::optional from lanes polygon (`#9288 `_) +* fix(lane_change): extending lane change path for multiple lane change (RT1-8427) (`#9268 `_) + * RT1-8427 extending lc path for multiple lc + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(lane_change): correct computation of maximum lane changing length threshold (`#9279 `_) + fix computation of maximum lane changing length threshold +* refactor(lane_change): revert "remove std::optional from lanes polygon" (`#9272 `_) + Revert "refactor(lane_change): remove std::optional from lanes polygon (`#9267 `_)" + This reverts commit 0c70ea8793985c6aae90f851eeffdd2561fe04b3. +* refactor(lane_change): remove std::optional from lanes polygon (`#9267 `_) +* fix(lane_change): enable cancel when ego in turn direction lane (`#9124 `_) + * RT0-33893 add checks from prev intersection + * fix shadow variable + * fix logic + * update readme + * refactor get_ego_footprint + --------- +* test(bpp_common): add unit test for safety check (`#9223 `_) + * add test for object collision + * add test for more functions + * add docstring + * fix lane change + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo, Zulfaqar Azmi, kobayu858, mkquda + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 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 d4108003a9afe..dd4dbe63e41d4 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 @@ -2,7 +2,7 @@ autoware_behavior_path_lane_change_module - 0.39.0 + 0.40.0 The autoware_behavior_path_lane_change_module package Fumiya Watanabe diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst index ea088d6130c85..654a5b4ed0d87 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/CHANGELOG.rst @@ -2,6 +2,50 @@ Changelog for package autoware_behavior_path_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* fix(bpp)!: remove stop reason (`#9449 `_) + fix(bpp): remove stop reason +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(bpp): add velocity interface (`#9344 `_) + * feat(bpp): add velocity interface + * fix(adapi): subscribe additional velocity factors + --------- +* refactor(factor): move steering factor interface to motion utils (`#9337 `_) +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml index 7fa591bd4a740..6141480d1597a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_planner - 0.39.0 + 0.40.0 The behavior_path_planner package diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst index 0e0b6aa328d26..6c72ac310e31f 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/CHANGELOG.rst @@ -2,6 +2,143 @@ Changelog for package autoware_behavior_path_planner_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* build(behavior_path_planner_common): fix #include (`#6297 `_) +* feat(behavior_path_planner): add detail text to virutal wall (`#9600 `_) + * feat(behavior_path_planner): add detail text to virutal wall + * goal is far + * pull over start pose is far + * fix lc build + * fix build + * Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp + --------- +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(lane_change): check obj predicted path when filtering (`#9385 `_) + * RT1-8537 check object's predicted path when filtering + * use ranges view in get_line_string_paths + * check only vehicle type predicted path + * Refactor naming + * fix grammatical + * Update planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> + * precommit and grammar fix + --------- + Co-authored-by: Maxime CLEMENT <78338830+maxime-clem@users.noreply.github.com> +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* test(bpp_common): add unit test for utils (`#9469 `_) + * add easy unit test + * fix clang tidy warning and add unit test + * add more unit test + * add docstring + --------- +* test(bpp_common): add unit test for object filtering (`#9408 `_) + * add unit test for all function + * add function to create bounding nox object + --------- +* test(bpp_common): add unit test for traffic light utils (`#9441 `_) + * add test data for traffic light utils + * add unit test function + * fix style + * use test_utils::resolve_plg_share_uri for map path + --------- +* fix(bpp)!: remove stop reason (`#9449 `_) + fix(bpp): remove stop reason +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(behavior_path_planner_common): add package maintainer (`#9429 `_) + add package maintainer +* refactor(lane_change): separate target lane leading based on obj behavior (`#9372 `_) + * separate target lane leading objects based on behavior (RT1-8532) + * fixed overlapped filtering and lanes debug marker + * combine filteredObjects function + * renaming functions and type + * update some logic to check is stopped + * rename expanded to stopped_outside_boundary + * Include docstring + * rename stopped_outside_boundary → stopped_at_bound + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> + * spell-check + --------- + Co-authored-by: mkquda <168697710+mkquda@users.noreply.github.com> +* refactor(goal_planner): rename shoulder_lane to pull_over_lane (`#9422 `_) +* fix(behavior_path_planner_common): prevent duplicated point insertion in cutOverlappedLanes (`#9363 `_) +* feat(behavior_path_planner_common): use azimuth for interpolatePose (`#9362 `_) +* test(bpp_common): add unit test for safety check (`#9386 `_) + * fix docstring + * add basic collision test + * add some more tests + * add unit test for all functions + * remove unecessary header and space + --------- +* refactor(traffic_light_utils): prefix package and namespace with autoware (`#9251 `_) +* feat(bpp): add velocity interface (`#9344 `_) + * feat(bpp): add velocity interface + * fix(adapi): subscribe additional velocity factors + --------- +* refactor(factor): move steering factor interface to motion utils (`#9337 `_) +* fix(bpp): update collided polygon pose only once (`#9338 `_) + * fix(bpp): update collided polygon pose only once + * add expected pose + --------- +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* test(bpp_common): add tests for the static drivable area (`#9324 `_) +* feat(goal_planner): safety check with only parking path (`#9293 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(behavior_path_planner_common): use boost intersects instead of overlaps (`#9289 `_) + * fix(behavior_path_planner_common): use boost intersects instead of overlaps + * Update planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp + Co-authored-by: Go Sakayori + --------- + Co-authored-by: Go Sakayori +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(bpp): prevent accessing nullopt (`#9269 `_) +* test(behavior_path_planner_common): add unit test for path shifter (`#9239 `_) + * add unit test for path shifter + * fix unnecessary modification + * fix spelling mistake + * add docstring + --------- +* test(bpp_common): add unit test for safety check (`#9223 `_) + * add test for object collision + * add test for more functions + * add docstring + * fix lane change + --------- +* fix(bpp): prevent accessing nullopt (`#9204 `_) + fix(bpp): calcDistanceToRedTrafficLight null +* Contributors: Esteve Fernandez, Felix F Xu, Fumiya Watanabe, Go Sakayori, Kosuke Takeuchi, M. Fatih Cırıt, Maxime CLEMENT, Ryohsuke Mitsudome, Satoshi OTA, Shumpei Wakabayashi, Yutaka Kondo, Zulfaqar Azmi, mkquda + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml index 40506ad74a274..f23a9980f1237 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_planner_common - 0.39.0 + 0.40.0 The autoware_behavior_path_planner_common package diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst index e823e6501df47..73fd1b4c7532a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/CHANGELOG.rst @@ -2,6 +2,49 @@ Changelog for package autoware_behavior_path_sampling_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_behavior_path_sampling_planner_module): fix clang-diagnostic-unused-variable (`#9404 `_) + fix: clang-diagnostic-unused-variable +* fix(autoware_behavior_path_sampling_planner_module): fix invalid parameter file (`#9231 `_) + Co-authored-by: Yutaka Kondo +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_behavior_path_sampling_planner_module): fix cppcheck unusedVariable (`#9190 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Satoshi OTA, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml index cd609a9dee40f..a5d78061448ed 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_sampling_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_sampling_planner_module - 0.39.0 + 0.40.0 The autoware_behavior_path_sampling_planner_module package Daniel Sanchez diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst index 58ab621b9c925..6ed62ffc8b913 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/CHANGELOG.rst @@ -2,6 +2,47 @@ Changelog for package autoware_behavior_path_side_shift_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* test(autoware_behavior_path_side_shift_module): add unit tests for util function (`#9540 `_) + test(side_shift_module): add unit tests +* refactor(autoware_behavior_path_side_shift_module): refactor shift length retrieval and improve path orientation handling (`#9539 `_) + refactor(side_shift_module): refactor shift length retrieval and improve path orientation handling +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kyoichi Sugahara, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml index 6eac60c2411fd..9bc2b608381fa 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_side_shift_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_side_shift_module - 0.39.0 + 0.40.0 The autoware_behavior_path_side_shift_module package Satoshi Ota diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst index cbf67c171ee03..0cb96bc9b3bf4 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/CHANGELOG.rst @@ -2,6 +2,70 @@ Changelog for package autoware_behavior_path_start_planner_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* feat(behavior_path_planner): add detail text to virutal wall (`#9600 `_) + * feat(behavior_path_planner): add detail text to virutal wall + * goal is far + * pull over start pose is far + * fix lc build + * fix build + * Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp + --------- +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* fix(autoware_freespace_planner, autoware_freespace_planning_algorithms): modify freespace planner to use node clock instead of system clock (`#9152 `_) + * Modified the autoware_freespace_planner and autoware_freespace_planning_algorithms packages to use the node clock instead of rclcpp detached clock. This allows the module to make use of sim time. Previously during simulation the parking trajectory would have system time in trajectory header messages causing downstream issues like non-clearance of trajectory buffers in motion planning based on elapsed time. + * style(pre-commit): autofix + * Updated the freespace planner instantiation call in the path planning modules + * style(pre-commit): autofix + * Updated tests for the utility functions + * style(pre-commit): autofix + --------- + Co-authored-by: Steven Brills + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(start_planner): use extended current lanes to fix turn signal issue (`#9487 `_) + fix current lanes issue +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_behavior_path_start_planner_module): fix clang-diagnostic-unused-variable (`#9405 `_) + fix: clang-diagnostic-unused-variable +* feat(start_planner): output velocity factor (`#9347 `_) +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* feat(start_planner, lane_departure_checker): speed up by updating polygons (`#9309 `_) + speed up by updating polygons +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_behavior_path_start_planner_module): fix cppcheck unreadVariable (`#9277 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Satoshi OTA, Yutaka Kondo, danielsanchezaran, kobayu858, stevenbrills + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml index 97f1a8569b132..c7cabb403f164 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_start_planner_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_start_planner_module - 0.39.0 + 0.40.0 The autoware_behavior_path_start_planner_module package Kosuke Takeuchi diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst index 5d2af19f9ce2e..e162c187de824 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/CHANGELOG.rst @@ -2,6 +2,82 @@ Changelog for package autoware_behavior_path_static_obstacle_avoidance_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* feat(behavior_path_planner): add detail text to virutal wall (`#9600 `_) + * feat(behavior_path_planner): add detail text to virutal wall + * goal is far + * pull over start pose is far + * fix lc build + * fix build + * Update planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp + --------- +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(autoware_behavior_path_static_obstacle_avoidance_module): add maintainer (`#9581 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* fix(avoidance): remove stop reason (`#9364 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* perf(static_obstacle_avoidance): use lanelet::utils instead of route handle for closest lanelet (`#9367 `_) + use lanelet::utils for performance improvement +* perf(static_obstacle_avoidance): remove redundant calculation related to lanelet functions (`#9355 `_) + * add traffic light distance and modified goal allowance to avoidance data + * add closest lanelet related variable to avoidanceData structure + * use route handler for checking closest lanelet + * use std::optional + --------- +* feat(avoidance): output velocity factor (`#9345 `_) +* fix(static_obstacle_avoidance): override setInitState (`#9340 `_) + override setInitState +* refactor(bpp): rework steering factor interface (`#9325 `_) + * refactor(bpp): rework steering factor interface + * refactor(soa): rework steering factor interface + * refactor(AbLC): rework steering factor interface + * refactor(doa): rework steering factor interface + * refactor(lc): rework steering factor interface + * refactor(gp): rework steering factor interface + * refactor(sp): rework steering factor interface + * refactor(sbp): rework steering factor interface + * refactor(ss): rework steering factor interface + --------- +* refactor(static obstacle avoidance): remove redundant calculation (`#9326 `_) + * refactor bases on clang tidy + * refactor extend backward length + * mover redundant calculation in getRoadShoulderDistance + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* test(bpp_common): add unit test for safety check (`#9223 `_) + * add test for object collision + * add test for more functions + * add docstring + * fix lane change + --------- +* feat(static_obstacle_avoidance): operator request for ambiguous vehicle (`#9205 `_) + * add operator request feature + * Update planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/src/scene.cpp + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> + --------- + Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> +* Contributors: Esteve Fernandez, Fumiya Watanabe, Go Sakayori, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml index 00f0db2224d5b..5446e33073b13 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml +++ b/planning/behavior_path_planner/autoware_behavior_path_static_obstacle_avoidance_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_path_static_obstacle_avoidance_module - 0.39.0 + 0.40.0 The autoware_behavior_path_static_obstacle_avoidance_module package Takamasa Horibe diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst index 6c312d3f90cb8..0826b1f8193a6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/CHANGELOG.rst @@ -2,6 +2,38 @@ Changelog for package autoware_behavior_velocity_blind_spot_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* ci(pre-commit): update cpplint to 2.0.0 (`#9557 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor(blind_spot): move util functions outside of class (`#9544 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* chore(blind_spot): divide headers to include/ (`#9534 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_behavior_velocity_blind_spot_module): fix clang-diagnostic-unused-parameter (`#9406 `_) + fix: clang-diagnostic-unused-parameter +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yutaka Kondo, awf-autoware-bot[bot], kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml index 1dd334f89c67f..a2ea4a82a884d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_blind_spot_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_blind_spot_module package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst index 8663879cc095f..608d6ab37fdc4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package autoware_behavior_velocity_crosswalk_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(crosswalk)!: delete wide crosswalk corresponding function (`#9329 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback (`#9234 `_) +* test(crosswalk): add unit test (`#9228 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Yuki TAKAGI, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml index 891a77e100435..6b939a7dd0be9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_crosswalk_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_crosswalk_module package Satoshi Ota diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst index f53d95a981950..fc13807261e4f 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/CHANGELOG.rst @@ -2,6 +2,44 @@ Changelog for package autoware_behavior_velocity_detection_area_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(behavior_velocity_planner): replace first_stop_path_point_index (`#9296 `_) + * feat(behavior_velocity_planner): replace first_stop_path_point_index + * add const + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp + Co-authored-by: Kosuke Takeuchi + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(detection_area)!: add retruction feature (`#9255 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yuki TAKAGI, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml index 1bd4e05af8447..ff91cf40a32a6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_detection_area_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_detection_area_module package Kyoichi Sugahara diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst index 4bd9f8487b644..013fd3b9b54cb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CHANGELOG.rst @@ -2,6 +2,46 @@ Changelog for package autoware_behavior_velocity_intersection_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* refactor: correct spelling (`#9528 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_behavior_velocity_intersection_module): fix clang-diagnostic-unused-parameter (`#9409 `_) + fix: clang-diagnostic-unused-parameter +* fix(autoware_behavior_velocity_intersection_module): fix clang-diagnostic-unused-lambda-capture (`#9407 `_) + fix: clang-diagnostic-unused-parameter +* chore(autoware_behavior_velocity_intersection_module): include opencv as system (`#9330 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(bvp): remove expired module safely (`#9212 `_) + * fix(bvp): remove expired module safely + * fix: remove module id set + * fix: use itr to erase expired module + * fix: remove unused function + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Yukinari Hisaki, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml index 16c7a13f21320..b056f71614da3 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_intersection_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_intersection_module package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst index 0d3e17d146747..3ad226a0a0f71 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_behavior_velocity_no_drivable_lane_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml index 524aeec6d6c6d..3ac9bab0c2fdf 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_no_drivable_lane_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_no_drivable_lane_module package Ahmed Ebrahim diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst index de6f32656fe5b..177028582aceb 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/CHANGELOG.rst @@ -2,6 +2,44 @@ Changelog for package autoware_behavior_velocity_no_stopping_area_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(behavior_velocity_planner): replace first_stop_path_point_index (`#9296 `_) + * feat(behavior_velocity_planner): replace first_stop_path_point_index + * add const + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp + Co-authored-by: Kosuke Takeuchi + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_behavior_velocity_no_stopping_area_module): fix cppcheck knownConditionTrueFalse (`#9189 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Ryuta Kambe, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml index 0873e3cd433d2..88fafeb5b90dc 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_no_stopping_area_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_no_stopping_area_module package Kosuke Takeuchi diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst index 695f4a63e3ae0..e74a81a6a971a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_behavior_velocity_occlusion_spot_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml index 9ce05294f86ed..66cb33192fec0 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_occlusion_spot_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_occlusion_spot_module package Taiki Tanaka diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst index eedb174bcd2c4..43eafef522dde 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/CHANGELOG.rst @@ -2,6 +2,57 @@ Changelog for package autoware_behavior_velocity_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files (`#9470 `_) + * refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files + * Update planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> + * fix + --------- + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_behavior_velocity_planner): fix clang-diagnostic-format-security (`#9411 `_) + fix: clang-diagnostic-format-security +* feat(behavior_velocity_planner): replace first_stop_path_point_index (`#9296 `_) + * feat(behavior_velocity_planner): replace first_stop_path_point_index + * add const + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp + Co-authored-by: Kosuke Takeuchi + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix(bvp): remove callback group (`#9294 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(bvp): use polling subscriber (`#9242 `_) + * fix(bvp): use polling subscriber + * fix: use newest policy + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Yukinari Hisaki, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml index a7a892e521826..8ba8272712364 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_planner - 0.39.0 + 0.40.0 The autoware_behavior_velocity_planner package Mamoru Sobue diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst index c702d7b763653..efc6fd8e18cb6 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/CHANGELOG.rst @@ -2,6 +2,66 @@ Changelog for package autoware_behavior_velocity_planner_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* test(autoware_behavior_velocity_planner_common): refactor and test autoware_behavior_velocity_planner_common (`#9551 `_) + * test(autoware_behavior_velocity_planner_common): refactor and test autoware_behavior_velocity_planner_common + * remove nodiscard + * update + * fix + * fix + * update + --------- +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files (`#9470 `_) + * refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files + * Update planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> + * fix + --------- + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_behavior_velocity_planner_common): fix clang-diagnostic-unused-const-variable (`#9413 `_) + fix: clang-diagnostic-unused-const-variable +* feat(behavior_velocity_planner): replace first_stop_path_point_index (`#9296 `_) + * feat(behavior_velocity_planner): replace first_stop_path_point_index + * add const + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp + Co-authored-by: Kosuke Takeuchi + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(bvp): remove expired module safely (`#9212 `_) + * fix(bvp): remove expired module safely + * fix: remove module id set + * fix: use itr to erase expired module + * fix: remove unused function + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Yukinari Hisaki, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml index 1e309ebd1caee..77b26aac09161 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_planner_common - 0.39.0 + 0.40.0 The autoware_behavior_velocity_planner_common package Tomoya Kimura diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst index ae2df69a585c0..eaf93783ae47a 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/CHANGELOG.rst @@ -2,6 +2,56 @@ Changelog for package autoware_behavior_velocity_run_out_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(behavior_velocity_planner): update velocity factor initialization for run out module (`#9352 `_) + feat(behavior_velocity_planner): update velocity factor initialization + Update the initialization of the velocity factor in the RunOutModule of the behavior_velocity_planner. The velocity factor is now initialized for the RUN_OUT behavior instead of the ROUTE_OBSTACLE behavior. +* fix(autoware_behavior_velocity_run_out_module): fix clang-diagnostic-unused-lambda-capture (`#9416 `_) + fix: clang-diagnostic-unused-lambda-capture +* feat(run_out_module): add tests to run out (`#9222 `_) + * WIP add tests for utils and path_utils + * add tests for utils and fix test path utils + * dynamic obstacles + * new tests and add function declarations + * add points for test of extractObstaclePointsWithinPolygon + * add state machine tests and other tests for dynamic obstacle + * remove unused test checks + * remove unused tests + * remove unwanted semicolons + * test + * add comments + * solve cpp-check limitation issue by removing namespaces + --------- +* fix(run_out): output velocity factor (`#9319 `_) + * fix(run_out): output velocity factor + * fix(adapi): subscribe run out velocity factor + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kyoichi Sugahara, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo, danielsanchezaran, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml index a5374f0e37bde..90e1d32198854 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_run_out_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_run_out_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_run_out_module package Tomohito Ando diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst index d21af6839aaab..f0a53b8d7124d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_behavior_velocity_speed_bump_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml index 6560a51b3a026..4940460ba52c1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_speed_bump_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_speed_bump_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_speed_bump_module package Tomoya Kimura diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst index 0fa84098defb2..c24c67ff81108 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/CHANGELOG.rst @@ -2,6 +2,56 @@ Changelog for package autoware_behavior_velocity_stop_line_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(autoware_behavior_velocity_stop_line_module): remove unused function (`#9591 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* refactor(autoware_behavior_velocity_stop_line_module): refactor and test (`#9424 `_) + * refactor(autoware_behavior_velocity_stop_line_module): refactor and test + * modify + * small changes + * update + * fix test error + * update + --------- +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(autoware_behavior_velocity_stop_line_module): add maintainer (`#9427 `_) +* feat(behavior_velocity_stop_line): replace autoware_motion_utils to autoware_trajectory (`#9299 `_) + * feat(behavior_velocity_stop_line): replace autoware_motion_utils to autoware_trajectory + * update + --------- +* feat(behavior_velocity_planner): replace first_stop_path_point_index (`#9296 `_) + * feat(behavior_velocity_planner): replace first_stop_path_point_index + * add const + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp + Co-authored-by: Kosuke Takeuchi + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Ryuta Kambe, Yukinari Hisaki, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml index 7489e03c6ead0..fd4b9f83ae998 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_stop_line_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_stop_line_module package Yukinari Hisaki diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst index a1a2e65e5d749..4fb540814a9f1 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_behavior_velocity_template_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Mamoru Sobue, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml index 2cae84e19929f..e808e7758bd65 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_template_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_template_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_template_module package Daniel Sanchez diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst index 1ae51ad5bf695..669882a37bbce 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/CHANGELOG.rst @@ -2,6 +2,52 @@ Changelog for package autoware_behavior_velocity_traffic_light_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* ci(pre-commit): autoupdate (`#8949 `_) + Co-authored-by: M. Fatih Cırıt +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files (`#9470 `_) + * refactor(autoware_behavior_velocity_planner_common,autoware_behavior_velocity_planner): separate param files + * Update planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> + * fix + --------- + Co-authored-by: Kyoichi Sugahara <32741405+kyoichi-sugahara@users.noreply.github.com> +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(traffic_light_utils): prefix package and namespace with autoware (`#9251 `_) +* feat(behavior_velocity_planner): replace first_stop_path_point_index (`#9296 `_) + * feat(behavior_velocity_planner): replace first_stop_path_point_index + * add const + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp + Co-authored-by: Kosuke Takeuchi + * Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/planner_manager.cpp + Co-authored-by: Kosuke Takeuchi + --------- + Co-authored-by: Kosuke Takeuchi +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yukinari Hisaki, Yutaka Kondo, awf-autoware-bot[bot] + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml index 0ded242b6a3cf..082973d9431e5 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_traffic_light_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_traffic_light_module package Satoshi Ota diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst index c0b26562f584c..731c1967b5a1d 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_behavior_velocity_virtual_traffic_light_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml index 581d03e71c06d..6d3bc68242d7c 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_virtual_traffic_light_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_virtual_traffic_light_module package Kosuke Takeuchi diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst index 69ea69091532b..40a8bcf82e7b9 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/CHANGELOG.rst @@ -2,6 +2,35 @@ Changelog for package autoware_behavior_velocity_walkway_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* feat(behavior_velocity_planner)!: remove stop_reason (`#9452 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(autoware_behavior_velocity_walkway_module): fix clang-diagnostic-unused-lambda-capture (`#9415 `_) + fix: clang-diagnostic-unused-lambda-capture +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Yutaka Kondo, kobayu858 + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml index 9c706e3e13cd0..5f1aea22855a4 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_walkway_module/package.xml @@ -2,7 +2,7 @@ autoware_behavior_velocity_walkway_module - 0.39.0 + 0.40.0 The autoware_behavior_velocity_walkway_module package Satoshi Ota diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst index e05c363a76192..118b555408997 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_motion_velocity_dynamic_obstacle_stop_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml index e66fb82704c05..eef7b6af1f9af 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_dynamic_obstacle_stop_module - 0.39.0 + 0.40.0 dynamic_obstacle_stop module to stop ego when in the immediate path of a dynamic object Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst index 844d4425a6afd..c1310671d02fa 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_motion_velocity_obstacle_velocity_limiter_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml index 268f331f86423..68e2ead5a5ec7 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/package.xml @@ -1,7 +1,7 @@ autoware_motion_velocity_obstacle_velocity_limiter_module - 0.39.0 + 0.40.0 Package to adjust velocities of a trajectory in order for the ride to feel safe Maxime CLEMENT diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst index 57a3918601976..4fe77d0532fce 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_motion_velocity_out_of_lane_module ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(traffic_light_utils): prefix package and namespace with autoware (`#9251 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(out_of_lane): correct calculations of the stop pose (`#9209 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Maxime CLEMENT, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml index 4001136b72ec0..857716819d8cc 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_out_of_lane_module - 0.39.0 + 0.40.0 The motion_velocity_out_of_lane_module package Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst index 3b353111d1055..50db2374baedc 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_motion_velocity_planner_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml index 650b3308d508b..3f0c027a5c986 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_planner_common - 0.39.0 + 0.40.0 Common functions and interfaces for motion_velocity_planner modules Maxime Clement diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst index 01fb10df7bd64..4a6dc3095391f 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/CHANGELOG.rst @@ -2,6 +2,56 @@ Changelog for package autoware_motion_velocity_planner_node ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kem (TiankuiXian), M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml index a28a24d4dae49..186140cba6e3c 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_node/package.xml @@ -2,7 +2,7 @@ autoware_motion_velocity_planner_node - 0.39.0 + 0.40.0 Node of the motion_velocity_planner Maxime Clement diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst b/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst index b3ab3bb13aa3c..fa7e4a3bb0808 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_bezier_sampler/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_bezier_sampler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/sampling_based_planner/autoware_bezier_sampler/package.xml b/planning/sampling_based_planner/autoware_bezier_sampler/package.xml index 9da456248f0ce..249d64d770af5 100644 --- a/planning/sampling_based_planner/autoware_bezier_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_bezier_sampler/package.xml @@ -1,7 +1,7 @@ autoware_bezier_sampler - 0.39.0 + 0.40.0 Package to sample trajectories using Bézier curves Maxime CLEMENT Maxime CLEMENT diff --git a/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst b/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst index e0123b1de0bd7..eff4108b3fc03 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_frenet_planner/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_frenet_planner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/sampling_based_planner/autoware_frenet_planner/package.xml b/planning/sampling_based_planner/autoware_frenet_planner/package.xml index 11608baabeb76..cd5febc3267db 100644 --- a/planning/sampling_based_planner/autoware_frenet_planner/package.xml +++ b/planning/sampling_based_planner/autoware_frenet_planner/package.xml @@ -1,7 +1,7 @@ autoware_frenet_planner - 0.39.0 + 0.40.0 The autoware_frenet_planner package for trajectory generation in Frenet frame Maxime CLEMENT Maxime CLEMENT diff --git a/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst b/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst index 33fb5a66d1ed6..a50f2a0ad3aed 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_path_sampler/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_path_sampler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(fake_test_node): prefix package and namespace with autoware (`#9249 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/sampling_based_planner/autoware_path_sampler/package.xml b/planning/sampling_based_planner/autoware_path_sampler/package.xml index 8f27509d27f67..142eafdfa4bfe 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/package.xml +++ b/planning/sampling_based_planner/autoware_path_sampler/package.xml @@ -2,7 +2,7 @@ autoware_path_sampler - 0.39.0 + 0.40.0 Package for the sampling-based path planner Maxime CLEMENT Apache License 2.0 diff --git a/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst b/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst index d07a47c0c4629..7e0eaaf4e7376 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst +++ b/planning/sampling_based_planner/autoware_sampler_common/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package autoware_sampler_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - planning (`#9570 `_) +* refactor: correct spelling (`#9528 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/planning/sampling_based_planner/autoware_sampler_common/package.xml b/planning/sampling_based_planner/autoware_sampler_common/package.xml index b5b4ab3bd9dc8..eb08c8125d3ee 100644 --- a/planning/sampling_based_planner/autoware_sampler_common/package.xml +++ b/planning/sampling_based_planner/autoware_sampler_common/package.xml @@ -1,7 +1,7 @@ autoware_sampler_common - 0.39.0 + 0.40.0 Common classes and functions for sampling based planners Maxime CLEMENT Maxime CLEMENT diff --git a/sensing/autoware_cuda_utils/CHANGELOG.rst b/sensing/autoware_cuda_utils/CHANGELOG.rst index 64b78ebc94eee..92a99bc8d3267 100644 --- a/sensing/autoware_cuda_utils/CHANGELOG.rst +++ b/sensing/autoware_cuda_utils/CHANGELOG.rst @@ -1,6 +1,36 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package autoware_cuda_utils -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix: fix package names in changelog files (`#9500 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* Revert "refactor(sensing): move CUDA related packages to `sensing/cuda` directory" (`#9394 `_) + Revert "refactor(sensing): move CUDA related packages to `sensing/cuda` direc…" + This reverts commit be8235d785597c41d01782ec35da862ba0906578. +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(cuda_utils): prefix package and namespace with autoware (`#9171 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo 0.39.0 (2024-11-25) ------------------- diff --git a/sensing/autoware_cuda_utils/package.xml b/sensing/autoware_cuda_utils/package.xml index 817aa395092aa..32a29133201ec 100644 --- a/sensing/autoware_cuda_utils/package.xml +++ b/sensing/autoware_cuda_utils/package.xml @@ -1,7 +1,7 @@ autoware_cuda_utils - 0.39.0 + 0.40.0 cuda utility library Daisuke Nishimatsu diff --git a/sensing/autoware_gnss_poser/CHANGELOG.rst b/sensing/autoware_gnss_poser/CHANGELOG.rst index 25713471aacbd..8195195c9b15c 100644 --- a/sensing/autoware_gnss_poser/CHANGELOG.rst +++ b/sensing/autoware_gnss_poser/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_gnss_poser ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/sensing/autoware_gnss_poser/package.xml b/sensing/autoware_gnss_poser/package.xml index 8304229b18a05..6414ccbabca3f 100644 --- a/sensing/autoware_gnss_poser/package.xml +++ b/sensing/autoware_gnss_poser/package.xml @@ -2,7 +2,7 @@ autoware_gnss_poser - 0.39.0 + 0.40.0 The ROS 2 autoware_gnss_poser package Yamato Ando Masahiro Sakamoto diff --git a/sensing/autoware_image_diagnostics/CHANGELOG.rst b/sensing/autoware_image_diagnostics/CHANGELOG.rst index db6df3ceedc67..1486e459e4754 100644 --- a/sensing/autoware_image_diagnostics/CHANGELOG.rst +++ b/sensing/autoware_image_diagnostics/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_image_diagnostics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - sensing (`#9571 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_image_diagnostics/package.xml b/sensing/autoware_image_diagnostics/package.xml index 48109cfd22e91..2e4556de2b92b 100644 --- a/sensing/autoware_image_diagnostics/package.xml +++ b/sensing/autoware_image_diagnostics/package.xml @@ -2,7 +2,7 @@ autoware_image_diagnostics - 0.39.0 + 0.40.0 The autoware_image_diagnostics package Dai Nguyen Yoshi Ri diff --git a/sensing/autoware_image_transport_decompressor/CHANGELOG.rst b/sensing/autoware_image_transport_decompressor/CHANGELOG.rst index fb82afbff8fe9..57968c49291c0 100644 --- a/sensing/autoware_image_transport_decompressor/CHANGELOG.rst +++ b/sensing/autoware_image_transport_decompressor/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_image_transport_decompressor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_image_transport_decompressor/package.xml b/sensing/autoware_image_transport_decompressor/package.xml index 22766b6582631..0ee5a60b2f46e 100644 --- a/sensing/autoware_image_transport_decompressor/package.xml +++ b/sensing/autoware_image_transport_decompressor/package.xml @@ -2,7 +2,7 @@ autoware_image_transport_decompressor - 0.39.0 + 0.40.0 The image_transport_decompressor package Yukihiro Saito Kenzo Lobos-Tsunekawa diff --git a/sensing/autoware_imu_corrector/CHANGELOG.rst b/sensing/autoware_imu_corrector/CHANGELOG.rst index 926cd3a195e0f..fe36ee24880e0 100644 --- a/sensing/autoware_imu_corrector/CHANGELOG.rst +++ b/sensing/autoware_imu_corrector/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_imu_corrector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - sensing (`#9571 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_imu_corrector/package.xml b/sensing/autoware_imu_corrector/package.xml index e32814af99863..94a2e3fe83071 100644 --- a/sensing/autoware_imu_corrector/package.xml +++ b/sensing/autoware_imu_corrector/package.xml @@ -2,7 +2,7 @@ autoware_imu_corrector - 0.39.0 + 0.40.0 The ROS 2 autoware_imu_corrector package Yamato Ando Taiki Yamada diff --git a/sensing/autoware_pcl_extensions/CHANGELOG.rst b/sensing/autoware_pcl_extensions/CHANGELOG.rst index ef8cc108086b5..56c9f0bdff0dc 100644 --- a/sensing/autoware_pcl_extensions/CHANGELOG.rst +++ b/sensing/autoware_pcl_extensions/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_pcl_extensions ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_pcl_extensions/package.xml b/sensing/autoware_pcl_extensions/package.xml index a141ebb31223f..840bd976b5b5f 100644 --- a/sensing/autoware_pcl_extensions/package.xml +++ b/sensing/autoware_pcl_extensions/package.xml @@ -2,7 +2,7 @@ autoware_pcl_extensions - 0.39.0 + 0.40.0 The autoware_pcl_extensions package Ryu Yamamoto Kenzo Lobos Tsunekawa diff --git a/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst b/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst index 6812ad076e60f..ad1ce2aaf8464 100644 --- a/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst +++ b/sensing/autoware_pointcloud_preprocessor/CHANGELOG.rst @@ -2,6 +2,50 @@ Changelog for package autoware_pointcloud_preprocessor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - sensing (`#9571 `_) +* fix(autoware_pointcloud_preprocessor): remove unused arg and unavailable param file. (`#9525 `_) + Remove unused arg and unavailable param file. +* fix(autoware_pointcloud_preprocessor): fix clang-diagnostic-inconsistent-missing-override (`#9445 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore: update license of pointcloud preprocessor (`#9397 `_) + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix(autoware_pointcloud_preprocessor): clang-tidy error in distortion corrector (`#9412 `_) + fix: clang-tidy +* fix(autoware_pointcloud_preprocessor): clang-tidy for overrides (`#9414 `_) + fix: clang-tidy for overrides +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_pointcloud_preprocessor): fix the wrong naming of crop box parameter file (`#9258 `_) + fix: fix the wrong file name +* fix(autoware_pointcloud_preprocessor): launch file load parameter from yaml (`#8129 `_) + * feat: fix launch file + * chore: fix spell error + * chore: fix parameters file name + * chore: remove filter base + --------- +* Contributors: Daisuke Nishimatsu, Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mukunda Bharatheesha, Ryohsuke Mitsudome, Ryuta Kambe, Yi-Hsiang Fang (Vivid), Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/sensing/autoware_pointcloud_preprocessor/package.xml b/sensing/autoware_pointcloud_preprocessor/package.xml index 20643d66d364c..4511c5497a3a0 100644 --- a/sensing/autoware_pointcloud_preprocessor/package.xml +++ b/sensing/autoware_pointcloud_preprocessor/package.xml @@ -2,7 +2,7 @@ autoware_pointcloud_preprocessor - 0.39.0 + 0.40.0 The ROS 2 autoware_pointcloud_preprocessor package amc-nu Yukihiro Saito diff --git a/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst b/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst index 8524887c25bff..4d92b7237c281 100644 --- a/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst +++ b/sensing/autoware_radar_scan_to_pointcloud2/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_radar_scan_to_pointcloud2 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_radar_scan_to_pointcloud2/package.xml b/sensing/autoware_radar_scan_to_pointcloud2/package.xml index 9dae0e583bc43..b14615cfb68ea 100644 --- a/sensing/autoware_radar_scan_to_pointcloud2/package.xml +++ b/sensing/autoware_radar_scan_to_pointcloud2/package.xml @@ -1,7 +1,7 @@ autoware_radar_scan_to_pointcloud2 - 0.39.0 + 0.40.0 autoware_radar_scan_to_pointcloud2 Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst b/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst index eba58b0fb6278..b66f99ba578a6 100644 --- a/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_static_pointcloud_filter/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_radar_static_pointcloud_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_radar_static_pointcloud_filter/package.xml b/sensing/autoware_radar_static_pointcloud_filter/package.xml index f685147f9d0a4..943bd71f29da7 100644 --- a/sensing/autoware_radar_static_pointcloud_filter/package.xml +++ b/sensing/autoware_radar_static_pointcloud_filter/package.xml @@ -1,7 +1,7 @@ autoware_radar_static_pointcloud_filter - 0.39.0 + 0.40.0 autoware_radar_static_pointcloud_filter Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_threshold_filter/CHANGELOG.rst b/sensing/autoware_radar_threshold_filter/CHANGELOG.rst index ef65bcc5f4fe4..e217daeca5a35 100644 --- a/sensing/autoware_radar_threshold_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_threshold_filter/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_radar_threshold_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_radar_threshold_filter/package.xml b/sensing/autoware_radar_threshold_filter/package.xml index 3127153fd9e30..5e2a5395168fb 100644 --- a/sensing/autoware_radar_threshold_filter/package.xml +++ b/sensing/autoware_radar_threshold_filter/package.xml @@ -1,7 +1,7 @@ autoware_radar_threshold_filter - 0.39.0 + 0.40.0 autoware_radar_threshold_filter Satoshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst b/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst index 29ff75fddd69a..c11a0fde76832 100644 --- a/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst +++ b/sensing/autoware_radar_tracks_noise_filter/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_radar_tracks_noise_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - sensing (`#9571 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_radar_tracks_noise_filter/package.xml b/sensing/autoware_radar_tracks_noise_filter/package.xml index af8db58a86567..d674e88e19a1a 100644 --- a/sensing/autoware_radar_tracks_noise_filter/package.xml +++ b/sensing/autoware_radar_tracks_noise_filter/package.xml @@ -2,7 +2,7 @@ autoware_radar_tracks_noise_filter - 0.39.0 + 0.40.0 autoware_radar_tracks_noise_filter Sathshi Tanaka Shunsuke Miura diff --git a/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst b/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst index 9f4f9e3e96395..004b045a12494 100644 --- a/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst +++ b/sensing/autoware_vehicle_velocity_converter/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package vehicle_velocity_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* refactor(vehicle_velocity_converter)!: prefix package and namespace with autoware (`#8967 `_) + * add autoware prefix + * fix conflict + --------- + Co-authored-by: Yamato Ando +* Contributors: Fumiya Watanabe, Masaki Baba, Ryohsuke Mitsudome + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/autoware_vehicle_velocity_converter/package.xml b/sensing/autoware_vehicle_velocity_converter/package.xml index ce4e36855a03a..cc5c555680562 100644 --- a/sensing/autoware_vehicle_velocity_converter/package.xml +++ b/sensing/autoware_vehicle_velocity_converter/package.xml @@ -2,7 +2,7 @@ autoware_vehicle_velocity_converter - 0.39.0 + 0.40.0 The autoware_vehicle_velocity_converter package Ryu Yamamoto Apache License 2.0 diff --git a/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst b/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst index 1721bb0e74007..e9e42a6e4e629 100644 --- a/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst +++ b/sensing/livox/autoware_livox_tag_filter/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package autoware_livox_tag_filter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/sensing/livox/autoware_livox_tag_filter/package.xml b/sensing/livox/autoware_livox_tag_filter/package.xml index adb2229745789..61555e186d1e1 100644 --- a/sensing/livox/autoware_livox_tag_filter/package.xml +++ b/sensing/livox/autoware_livox_tag_filter/package.xml @@ -2,7 +2,7 @@ autoware_livox_tag_filter - 0.39.0 + 0.40.0 The autoware_livox_tag_filter package Ryohsuke Mitsudome Kenzo Lobos-Tsunekawa diff --git a/simulator/autoware_carla_interface/CHANGELOG.rst b/simulator/autoware_carla_interface/CHANGELOG.rst index bdc1cc41bd5e0..d71cf66049c9d 100644 --- a/simulator/autoware_carla_interface/CHANGELOG.rst +++ b/simulator/autoware_carla_interface/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_carla_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(autoware_carla_interface): include "modules" submodule in release package and update setup.py (`#9561 `_) +* feat!: replace tier4_map_msgs with autoware_map_msgs for MapProjectorInfo (`#9392 `_) +* refactor: correct spelling (`#9528 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Jesus Armando Anaya, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/simulator/autoware_carla_interface/package.xml b/simulator/autoware_carla_interface/package.xml index 215a7c778523f..1ea183cc86eb5 100644 --- a/simulator/autoware_carla_interface/package.xml +++ b/simulator/autoware_carla_interface/package.xml @@ -1,7 +1,7 @@ autoware_carla_interface - 0.39.0 + 0.40.0 The carla autoware bridge package Muhammad Raditya GIOVANNI Maxime CLEMENT diff --git a/simulator/autoware_carla_interface/setup.py b/simulator/autoware_carla_interface/setup.py index 84f7a544555a2..4f06766582f6a 100644 --- a/simulator/autoware_carla_interface/setup.py +++ b/simulator/autoware_carla_interface/setup.py @@ -8,7 +8,7 @@ setup( name=package_name, - version="0.38.0", + version="0.40.0", packages=find_packages(where="src"), data_files=[ ("share/ament_index/resource_index/packages", [f"resource/{package_name}"]), diff --git a/simulator/dummy_perception_publisher/CHANGELOG.rst b/simulator/dummy_perception_publisher/CHANGELOG.rst index d0483f9ebe480..50b2396ae0311 100644 --- a/simulator/dummy_perception_publisher/CHANGELOG.rst +++ b/simulator/dummy_perception_publisher/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package dummy_perception_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - simulator (`#9572 `_) +* fix(dummy_perception_publisher): fix clang-diagnostic-unused-private-field (`#9447 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/simulator/dummy_perception_publisher/package.xml b/simulator/dummy_perception_publisher/package.xml index f2b60ce3ef857..4f78acd6c07f2 100644 --- a/simulator/dummy_perception_publisher/package.xml +++ b/simulator/dummy_perception_publisher/package.xml @@ -2,7 +2,7 @@ dummy_perception_publisher - 0.39.0 + 0.40.0 The dummy_perception_publisher package Yukihiro Saito Apache License 2.0 diff --git a/simulator/fault_injection/CHANGELOG.rst b/simulator/fault_injection/CHANGELOG.rst index 74ec3b4a867f4..6116bafaa2088 100644 --- a/simulator/fault_injection/CHANGELOG.rst +++ b/simulator/fault_injection/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package fault_injection ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - simulator (`#9572 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/simulator/fault_injection/package.xml b/simulator/fault_injection/package.xml index 25a5ceddd31be..feedcf3333f7f 100644 --- a/simulator/fault_injection/package.xml +++ b/simulator/fault_injection/package.xml @@ -2,7 +2,7 @@ fault_injection - 0.39.0 + 0.40.0 fault_injection Keisuke Shima Apache License 2.0 diff --git a/simulator/learning_based_vehicle_model/CHANGELOG.rst b/simulator/learning_based_vehicle_model/CHANGELOG.rst index b902713689ab1..ed271370a6840 100644 --- a/simulator/learning_based_vehicle_model/CHANGELOG.rst +++ b/simulator/learning_based_vehicle_model/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package learning_based_vehicle_model ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - simulator (`#9572 `_) +* fix(learning_based_vehicle_model): fix clang-diagnostic-delete-abstract-non-virtual-dtor (`#9446 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/simulator/learning_based_vehicle_model/package.xml b/simulator/learning_based_vehicle_model/package.xml index 11b5b2f88db03..317be3d0990ca 100644 --- a/simulator/learning_based_vehicle_model/package.xml +++ b/simulator/learning_based_vehicle_model/package.xml @@ -2,7 +2,7 @@ learning_based_vehicle_model - 0.39.0 + 0.40.0 learning_based_vehicle_model for simple_planning_simulator Maxime Clement Tomas Nagy diff --git a/simulator/simple_planning_simulator/CHANGELOG.rst b/simulator/simple_planning_simulator/CHANGELOG.rst index 7b995d36dbf83..ac6e093ea55e7 100644 --- a/simulator/simple_planning_simulator/CHANGELOG.rst +++ b/simulator/simple_planning_simulator/CHANGELOG.rst @@ -2,6 +2,39 @@ Changelog for package simple_planning_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - simulator (`#9572 `_) +* fix(simple_planning_simulator): fix clang-diagnostic-delete-non-abstract-non-virtual-dtor (`#9448 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(simple_planning_simulator): add mechanical actuaion sim model (`#9300 `_) + * feat(simple_planning_simulator): add mechanical actuaion sim model + update docs + * update from suggestions + * calc internal state using RK4 results + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index a6f86dd6e8a4b..fdc782182f9a5 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -2,7 +2,7 @@ simple_planning_simulator - 0.39.0 + 0.40.0 simple_planning_simulator as a ROS 2 node Takamasa Horibe Tomoya Kimura diff --git a/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst b/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst index 1d5b1d454a4a7..1157abff775ab 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst +++ b/simulator/tier4_dummy_object_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package tier4_dummy_object_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - simulator (`#9572 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix(tier4_dummy_object_rviz_plugin): fix missing dependency (`#9306 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/simulator/tier4_dummy_object_rviz_plugin/package.xml b/simulator/tier4_dummy_object_rviz_plugin/package.xml index c5ef8a68eb98f..b73d3a1cc15c0 100644 --- a/simulator/tier4_dummy_object_rviz_plugin/package.xml +++ b/simulator/tier4_dummy_object_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_dummy_object_rviz_plugin - 0.39.0 + 0.40.0 The tier4_dummy_object_rviz_plugin package Yukihiro Saito Apache License 2.0 diff --git a/simulator/vehicle_door_simulator/CHANGELOG.rst b/simulator/vehicle_door_simulator/CHANGELOG.rst index 105292a8e63e1..3def98ed36995 100644 --- a/simulator/vehicle_door_simulator/CHANGELOG.rst +++ b/simulator/vehicle_door_simulator/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package vehicle_door_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/simulator/vehicle_door_simulator/package.xml b/simulator/vehicle_door_simulator/package.xml index 008fcb9500bfe..ca9d7c98e691a 100644 --- a/simulator/vehicle_door_simulator/package.xml +++ b/simulator/vehicle_door_simulator/package.xml @@ -2,7 +2,7 @@ vehicle_door_simulator - 0.39.0 + 0.40.0 The vehicle_door_simulator package Takagi, Isamu Apache License 2.0 diff --git a/system/autoware_component_monitor/CHANGELOG.rst b/system/autoware_component_monitor/CHANGELOG.rst index 224edb28d1c45..339f30f9f9f80 100644 --- a/system/autoware_component_monitor/CHANGELOG.rst +++ b/system/autoware_component_monitor/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_component_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* ci(pre-commit): update cpplint to 2.0.0 (`#9557 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo, awf-autoware-bot[bot] + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/autoware_component_monitor/package.xml b/system/autoware_component_monitor/package.xml index 5655c495b0aa7..27432bc1fc0d6 100644 --- a/system/autoware_component_monitor/package.xml +++ b/system/autoware_component_monitor/package.xml @@ -2,7 +2,7 @@ autoware_component_monitor - 0.39.0 + 0.40.0 A ROS 2 package to monitor system usage of component containers. Mehmet Emin Başoğlu Barış Zeren diff --git a/system/autoware_default_adapi/CHANGELOG.rst b/system/autoware_default_adapi/CHANGELOG.rst index 64f7326264a58..438ee15f16f61 100644 --- a/system/autoware_default_adapi/CHANGELOG.rst +++ b/system/autoware_default_adapi/CHANGELOG.rst @@ -2,6 +2,54 @@ Changelog for package autoware_default_adapi ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(bpp): add velocity interface (`#9344 `_) + * feat(bpp): add velocity interface + * fix(adapi): subscribe additional velocity factors + --------- +* fix(run_out): output velocity factor (`#9319 `_) + * fix(run_out): output velocity factor + * fix(adapi): subscribe run out velocity factor + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(autoware_default_adapi): change subscribing steering factor topic name for obstacle avoidance and lane changes (`#9273 `_) + feat(planning): add new steering factor topics for obstacle avoidance and lane changes +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kyoichi Sugahara, M. Fatih Cırıt, Ryohsuke Mitsudome, Satoshi OTA, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/system/autoware_default_adapi/package.xml b/system/autoware_default_adapi/package.xml index d04c476a45ae7..a24d0c8a30b62 100644 --- a/system/autoware_default_adapi/package.xml +++ b/system/autoware_default_adapi/package.xml @@ -2,7 +2,7 @@ autoware_default_adapi - 0.39.0 + 0.40.0 The autoware_default_adapi package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/autoware_processing_time_checker/CHANGELOG.rst b/system/autoware_processing_time_checker/CHANGELOG.rst index 96df106a6e4eb..39bf68af5f415 100644 --- a/system/autoware_processing_time_checker/CHANGELOG.rst +++ b/system/autoware_processing_time_checker/CHANGELOG.rst @@ -2,6 +2,62 @@ Changelog for package autoware_processing_time_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(autoware_processing_time_checker): fix typo (`#9504 `_) +* feat(autoware_processing_time_checker): add a trigger to choice whether to output metrics to log folder (`#9479 `_) + * add output_metrics option. + * move param set from config to launch file. + * fix bug. + --------- +* feat(processing_time_checker): update processing time list (`#9350 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(tier4_metric_msgs): apply tier4_metric_msgs for scenario_simulator_v2_adapter, control_evaluator, planning_evaluator, autonomous_emergency_braking, obstacle_cruise_planner, motion_velocity_planner, processing_time_checker (`#9180 `_) + * first commit + * fix building errs. + * change diagnostic messages to metric messages for publishing decision. + * fix bug about motion_velocity_planner + * change the diagnostic msg to metric msg in autoware_obstacle_cruise_planner. + * tmp save for planning_evaluator + * change the topic to which metrics published to. + * fix typo. + * remove unnesessary publishing of metrics. + * mke planning_evaluator publish msg of MetricArray instead of Diags. + * update aeb with metric type for decision. + * fix some bug + * remove autoware_evaluator_utils package. + * remove diagnostic_msgs dependency of planning_evaluator + * use metric_msgs for autoware_processing_time_checker. + * rewrite diagnostic_convertor to scenario_simulator_v2_adapter, supporting metric_msgs. + * pre-commit and fix typo + * publish metrics even if there is no metric in the MetricArray. + * modify the metric name of processing_time. + * update unit test for test_planning/control_evaluator + * manual pre-commit + --------- +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Kazunori-Nakajima, Kem (TiankuiXian), Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/system/autoware_processing_time_checker/package.xml b/system/autoware_processing_time_checker/package.xml index 17b4599197407..4a18857663cc1 100644 --- a/system/autoware_processing_time_checker/package.xml +++ b/system/autoware_processing_time_checker/package.xml @@ -2,7 +2,7 @@ autoware_processing_time_checker - 0.39.0 + 0.40.0 A package to find out nodes with common names Takayuki Murooka Kosuke Takeuchi diff --git a/system/bluetooth_monitor/CHANGELOG.rst b/system/bluetooth_monitor/CHANGELOG.rst index 96056c8907c86..25b55a9bdcc6f 100644 --- a/system/bluetooth_monitor/CHANGELOG.rst +++ b/system/bluetooth_monitor/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package bluetooth_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/bluetooth_monitor/package.xml b/system/bluetooth_monitor/package.xml index dfa77dd303427..f43db39e987b7 100644 --- a/system/bluetooth_monitor/package.xml +++ b/system/bluetooth_monitor/package.xml @@ -2,7 +2,7 @@ bluetooth_monitor - 0.39.0 + 0.40.0 Bluetooth alive monitoring Fumihito Ito Apache License 2.0 diff --git a/system/component_state_monitor/CHANGELOG.rst b/system/component_state_monitor/CHANGELOG.rst index 97281628626c3..40843314ddf4a 100644 --- a/system/component_state_monitor/CHANGELOG.rst +++ b/system/component_state_monitor/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package component_state_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/component_state_monitor/package.xml b/system/component_state_monitor/package.xml index 60dde0d93581b..b92dd4af9517f 100644 --- a/system/component_state_monitor/package.xml +++ b/system/component_state_monitor/package.xml @@ -2,7 +2,7 @@ component_state_monitor - 0.39.0 + 0.40.0 The component_state_monitor package Takagi, Isamu Apache License 2.0 diff --git a/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst b/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst index c60bb8204eb3e..b0d8f9b49cd59 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst +++ b/system/default_ad_api_helpers/ad_api_adaptors/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package ad_api_adaptors ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/system/default_ad_api_helpers/ad_api_adaptors/package.xml b/system/default_ad_api_helpers/ad_api_adaptors/package.xml index c91edb9232444..4fe6390df77e0 100644 --- a/system/default_ad_api_helpers/ad_api_adaptors/package.xml +++ b/system/default_ad_api_helpers/ad_api_adaptors/package.xml @@ -2,7 +2,7 @@ ad_api_adaptors - 0.39.0 + 0.40.0 The ad_api_adaptors package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst b/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst index 5961ee96c28d1..d44fe830e75db 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst +++ b/system/default_ad_api_helpers/ad_api_visualizers/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package ad_api_visualizers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/default_ad_api_helpers/ad_api_visualizers/package.xml b/system/default_ad_api_helpers/ad_api_visualizers/package.xml index b05fe7222b923..2392cfaaface1 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/package.xml +++ b/system/default_ad_api_helpers/ad_api_visualizers/package.xml @@ -2,7 +2,7 @@ ad_api_visualizers - 0.39.0 + 0.40.0 The ad_api_visualizers package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/default_ad_api_helpers/ad_api_visualizers/setup.py b/system/default_ad_api_helpers/ad_api_visualizers/setup.py index b088271ba74a7..ee4cf253b5288 100644 --- a/system/default_ad_api_helpers/ad_api_visualizers/setup.py +++ b/system/default_ad_api_helpers/ad_api_visualizers/setup.py @@ -11,7 +11,7 @@ setup( name=package_name, - version="0.39.0", + version="0.40.0", packages=[package_name], data_files=[ ("share/ament_index/resource_index/packages", [f"resource/{package_name}"]), diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst b/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst index 795fe18c58e29..819a580c87f43 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst +++ b/system/default_ad_api_helpers/automatic_pose_initializer/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package automatic_pose_initializer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* refactor(autoware_ad_api_specs): prefix package and namespace with autoware (`#9250 `_) + * refactor(autoware_ad_api_specs): prefix package and namespace with autoware + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * style(pre-commit): autofix + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api to adapi + * chore(autoware_adapi_specs): rename ad_api_specs to adapi_specs + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* refactor(component_interface_utils): prefix package and namespace with autoware (`#9092 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml index 7a0566f478118..13f15d7dc63fd 100644 --- a/system/default_ad_api_helpers/automatic_pose_initializer/package.xml +++ b/system/default_ad_api_helpers/automatic_pose_initializer/package.xml @@ -2,7 +2,7 @@ automatic_pose_initializer - 0.39.0 + 0.40.0 The automatic_pose_initializer package Takagi, Isamu Ryohsuke Mitsudome diff --git a/system/diagnostic_graph_aggregator/CHANGELOG.rst b/system/diagnostic_graph_aggregator/CHANGELOG.rst index c3824be814e01..51abe33dcfbdf 100644 --- a/system/diagnostic_graph_aggregator/CHANGELOG.rst +++ b/system/diagnostic_graph_aggregator/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package diagnostic_graph_aggregator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(diagnostic_graph_aggregator): implement diagnostic graph dump functionality (`#9261 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/system/diagnostic_graph_aggregator/package.xml b/system/diagnostic_graph_aggregator/package.xml index 0b58afa330f43..ae9266a3bf302 100644 --- a/system/diagnostic_graph_aggregator/package.xml +++ b/system/diagnostic_graph_aggregator/package.xml @@ -2,7 +2,7 @@ diagnostic_graph_aggregator - 0.39.0 + 0.40.0 The diagnostic_graph_aggregator package Takagi, Isamu Apache License 2.0 diff --git a/system/diagnostic_graph_utils/CHANGELOG.rst b/system/diagnostic_graph_utils/CHANGELOG.rst index 17643d9e955e5..857671f77fd94 100644 --- a/system/diagnostic_graph_utils/CHANGELOG.rst +++ b/system/diagnostic_graph_utils/CHANGELOG.rst @@ -2,6 +2,45 @@ Changelog for package diagnostic_graph_utils ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* feat(diagnostic_graph_utils): publish error graph instead of the terminal log (`#9421 `_) + * feat(diagnostic_graph_utils): publish error graph instead of the terminal log + * update + * fix + * Update system/diagnostic_graph_utils/src/node/logging.cpp + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> + * error_graph -> error_graph_text + --------- + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* fix(diagnostic_graph_utils): fix clang-diagnostic-delete-abstract-non-virtual-dtor (`#9431 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(diagnostic_graph_utils): reset graph when new one is received (`#9208 `_) + fix(diagnostic_graph_utils): reset graph when new one is reveived +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Takagi, Isamu, Takayuki Murooka, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/system/diagnostic_graph_utils/package.xml b/system/diagnostic_graph_utils/package.xml index 69b8e4083356d..03cf1fa369774 100644 --- a/system/diagnostic_graph_utils/package.xml +++ b/system/diagnostic_graph_utils/package.xml @@ -2,7 +2,7 @@ diagnostic_graph_utils - 0.39.0 + 0.40.0 The diagnostic_graph_utils package Takagi, Isamu Apache License 2.0 diff --git a/system/dummy_diag_publisher/CHANGELOG.rst b/system/dummy_diag_publisher/CHANGELOG.rst index 7f50608ce061b..4652837056220 100644 --- a/system/dummy_diag_publisher/CHANGELOG.rst +++ b/system/dummy_diag_publisher/CHANGELOG.rst @@ -2,6 +2,42 @@ Changelog for package dummy_diag_publisher ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* fix(dummy_diag_publisher): not use diagnostic_updater and param callback (`#9257 `_) + * fix(dummy_diag_publisher): not use diagnostic_updater and param callback for v0.29.0 (`#1414 `_) + fix(dummy_diag_publisher): not use diagnostic_updater and param callback + Co-authored-by: h-ohta + * fix: resolve build error of dummy diag publisher (`#1415 `_) + fix merge conflict + --------- + Co-authored-by: Shohei Sakai + Co-authored-by: h-ohta +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yuki TAKAGI, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/system/dummy_diag_publisher/package.xml b/system/dummy_diag_publisher/package.xml index d5693da6db8c6..56faf31413e77 100644 --- a/system/dummy_diag_publisher/package.xml +++ b/system/dummy_diag_publisher/package.xml @@ -2,7 +2,7 @@ dummy_diag_publisher - 0.39.0 + 0.40.0 The dummy_diag_publisher ROS 2 package Fumihito Ito TetsuKawa diff --git a/system/dummy_infrastructure/CHANGELOG.rst b/system/dummy_infrastructure/CHANGELOG.rst index e7ce27fe644e7..50ecdd8d7fa96 100644 --- a/system/dummy_infrastructure/CHANGELOG.rst +++ b/system/dummy_infrastructure/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package dummy_infrastructure ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/dummy_infrastructure/package.xml b/system/dummy_infrastructure/package.xml index b72927cd47162..49c1b00757094 100644 --- a/system/dummy_infrastructure/package.xml +++ b/system/dummy_infrastructure/package.xml @@ -2,7 +2,7 @@ dummy_infrastructure - 0.39.0 + 0.40.0 dummy_infrastructure Ryohsuke Mitsudome Apache License 2.0 diff --git a/system/duplicated_node_checker/CHANGELOG.rst b/system/duplicated_node_checker/CHANGELOG.rst index d44d9508aac6c..605012c898598 100644 --- a/system/duplicated_node_checker/CHANGELOG.rst +++ b/system/duplicated_node_checker/CHANGELOG.rst @@ -2,6 +2,33 @@ Changelog for package duplicated_node_checker ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* feat(duplicated_node_checker): show the node name on the terminal (`#9609 `_) +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Takayuki Murooka, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/duplicated_node_checker/package.xml b/system/duplicated_node_checker/package.xml index 12eb39f8ead30..ee2f938cfb442 100644 --- a/system/duplicated_node_checker/package.xml +++ b/system/duplicated_node_checker/package.xml @@ -2,7 +2,7 @@ duplicated_node_checker - 0.39.0 + 0.40.0 A package to find out nodes with common names Shumpei Wakabayashi yliuhb diff --git a/system/hazard_status_converter/CHANGELOG.rst b/system/hazard_status_converter/CHANGELOG.rst index d3f4488b00836..a0c8e0ae193d1 100644 --- a/system/hazard_status_converter/CHANGELOG.rst +++ b/system/hazard_status_converter/CHANGELOG.rst @@ -2,6 +2,41 @@ Changelog for package hazard_status_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(hazard_status_converter): hazard status converter subscribe emergency holding (`#9287 `_) + * feat: add subscriber for emergency_holding + * modify: fix value name + * style(pre-commit): autofix + * feat: add const to is_emergency_holding + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> + Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com> +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, TetsuKawa, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/hazard_status_converter/package.xml b/system/hazard_status_converter/package.xml index e53847459ea39..80cc53c08e16d 100644 --- a/system/hazard_status_converter/package.xml +++ b/system/hazard_status_converter/package.xml @@ -2,7 +2,7 @@ hazard_status_converter - 0.39.0 + 0.40.0 The hazard_status_converter package Takagi, Isamu Apache License 2.0 diff --git a/system/mrm_comfortable_stop_operator/CHANGELOG.rst b/system/mrm_comfortable_stop_operator/CHANGELOG.rst index fc403b6a366ff..cf423a3d7b158 100644 --- a/system/mrm_comfortable_stop_operator/CHANGELOG.rst +++ b/system/mrm_comfortable_stop_operator/CHANGELOG.rst @@ -2,6 +2,36 @@ Changelog for package mrm_comfortable_stop_operator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(mrm_comfortable_stop_operator): add updateParam for mrm comfortable stop (`#9353 `_) + * add updateParam for mrm comfortable stop + * remove abs since it is not necessary + --------- +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, danielsanchezaran + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/mrm_comfortable_stop_operator/package.xml b/system/mrm_comfortable_stop_operator/package.xml index ec8508f691439..58ff309d825f1 100644 --- a/system/mrm_comfortable_stop_operator/package.xml +++ b/system/mrm_comfortable_stop_operator/package.xml @@ -2,7 +2,7 @@ mrm_comfortable_stop_operator - 0.39.0 + 0.40.0 The MRM comfortable stop operator package Makoto Kurihara Tomohito Ando diff --git a/system/mrm_emergency_stop_operator/CHANGELOG.rst b/system/mrm_emergency_stop_operator/CHANGELOG.rst index 6ace9fa84cc90..f6dc5499bcb74 100644 --- a/system/mrm_emergency_stop_operator/CHANGELOG.rst +++ b/system/mrm_emergency_stop_operator/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package mrm_emergency_stop_operator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/mrm_emergency_stop_operator/package.xml b/system/mrm_emergency_stop_operator/package.xml index 8be2e83484c17..7614373672f31 100644 --- a/system/mrm_emergency_stop_operator/package.xml +++ b/system/mrm_emergency_stop_operator/package.xml @@ -2,7 +2,7 @@ mrm_emergency_stop_operator - 0.39.0 + 0.40.0 The MRM emergency stop operator package Makoto Kurihara Tomohito Ando diff --git a/system/mrm_handler/CHANGELOG.rst b/system/mrm_handler/CHANGELOG.rst index 4792246b01e86..d9e6990373f6f 100644 --- a/system/mrm_handler/CHANGELOG.rst +++ b/system/mrm_handler/CHANGELOG.rst @@ -2,6 +2,37 @@ Changelog for package mrm_handler ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* feat(mrm_handler): mrm handler publish emergecy holding (`#9285 `_) + * feat: add publisher for emrgency holding + * modify: fix msg element + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, TetsuKawa, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/mrm_handler/package.xml b/system/mrm_handler/package.xml index 78d6b631799bf..d330680e87049 100644 --- a/system/mrm_handler/package.xml +++ b/system/mrm_handler/package.xml @@ -2,7 +2,7 @@ mrm_handler - 0.39.0 + 0.40.0 The mrm_handler ROS 2 package Makoto Kurihara Ryuta Kambe diff --git a/system/system_diagnostic_monitor/CHANGELOG.rst b/system/system_diagnostic_monitor/CHANGELOG.rst index faf15ad273924..9a5721b05d7ee 100644 --- a/system/system_diagnostic_monitor/CHANGELOG.rst +++ b/system/system_diagnostic_monitor/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package system_diagnostic_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/system_diagnostic_monitor/package.xml b/system/system_diagnostic_monitor/package.xml index 657268589c5a2..095d7cf040517 100644 --- a/system/system_diagnostic_monitor/package.xml +++ b/system/system_diagnostic_monitor/package.xml @@ -2,7 +2,7 @@ system_diagnostic_monitor - 0.39.0 + 0.40.0 The system_diagnostic_monitor package Takagi, Isamu Apache License 2.0 diff --git a/system/system_monitor/CHANGELOG.rst b/system/system_monitor/CHANGELOG.rst index 7759f315830d2..0ce1977dfdfa8 100644 --- a/system/system_monitor/CHANGELOG.rst +++ b/system/system_monitor/CHANGELOG.rst @@ -2,6 +2,43 @@ Changelog for package system_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* ci(pre-commit): update cpplint to 2.0.0 (`#9557 `_) +* fix(cpplint): include what you use - system (`#9573 `_) +* 0.39.0 +* update changelog +* Merge commit '6a1ddbd08bd' into release-0.39.0 +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* feat(system_monitor): add on/off config for network traffic monitor (`#9069 `_) + * feat(system_monitor): add config for network traffic monitor + * fix: change function name from stop to skip + --------- +* feat(system_monitor): support loopback network interface (`#9067 `_) + * feat(system_monitor): support loopback network interface + * style(pre-commit): autofix + --------- + Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, awf-autoware-bot[bot], iwatake + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/system/system_monitor/package.xml b/system/system_monitor/package.xml index 1044cb2fde474..df63dac90551c 100644 --- a/system/system_monitor/package.xml +++ b/system/system_monitor/package.xml @@ -2,7 +2,7 @@ system_monitor - 0.39.0 + 0.40.0 The system_monitor package Fumihito Ito TetsuKawa diff --git a/system/topic_state_monitor/CHANGELOG.rst b/system/topic_state_monitor/CHANGELOG.rst index 6f7c71abcf683..1eebcd1bcb1b1 100644 --- a/system/topic_state_monitor/CHANGELOG.rst +++ b/system/topic_state_monitor/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package topic_state_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/topic_state_monitor/package.xml b/system/topic_state_monitor/package.xml index b6e517aec34bb..0468db6124666 100644 --- a/system/topic_state_monitor/package.xml +++ b/system/topic_state_monitor/package.xml @@ -2,7 +2,7 @@ topic_state_monitor - 0.39.0 + 0.40.0 The topic_state_monitor package Ryohsuke Mitsudome Apache License 2.0 diff --git a/system/velodyne_monitor/CHANGELOG.rst b/system/velodyne_monitor/CHANGELOG.rst index 717865b43d5ea..4cc3be4c7a3f0 100644 --- a/system/velodyne_monitor/CHANGELOG.rst +++ b/system/velodyne_monitor/CHANGELOG.rst @@ -2,6 +2,30 @@ Changelog for package velodyne_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/system/velodyne_monitor/package.xml b/system/velodyne_monitor/package.xml index 665e6ab87c575..0dc8ae5f00a5d 100644 --- a/system/velodyne_monitor/package.xml +++ b/system/velodyne_monitor/package.xml @@ -2,7 +2,7 @@ velodyne_monitor - 0.39.0 + 0.40.0 The velodyne_monitor package Fumihito Ito Apache License 2.0 diff --git a/tools/reaction_analyzer/CHANGELOG.rst b/tools/reaction_analyzer/CHANGELOG.rst index 740affa42f42a..f2f1ac255fc06 100644 --- a/tools/reaction_analyzer/CHANGELOG.rst +++ b/tools/reaction_analyzer/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package reaction_analyzer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - tools (`#9574 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/tools/reaction_analyzer/package.xml b/tools/reaction_analyzer/package.xml index b3b1f69421fe7..540376e032743 100644 --- a/tools/reaction_analyzer/package.xml +++ b/tools/reaction_analyzer/package.xml @@ -2,7 +2,7 @@ reaction_analyzer - 0.39.0 + 0.40.0 Analyzer that measures reaction times of the nodes Berkay Karaman diff --git a/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst b/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst index b53b0b225a141..cbd3907bd854a 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst +++ b/vehicle/autoware_accel_brake_map_calibrator/CHANGELOG.rst @@ -2,6 +2,34 @@ Changelog for package autoware_accel_brake_map_calibrator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - vehicle (`#9575 `_) +* ci(pre-commit): autoupdate (`#8949 `_) + Co-authored-by: M. Fatih Cırıt +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo, awf-autoware-bot[bot] + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/vehicle/autoware_accel_brake_map_calibrator/package.xml b/vehicle/autoware_accel_brake_map_calibrator/package.xml index 00ed9af04e5da..de2dcf2d8e440 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/package.xml +++ b/vehicle/autoware_accel_brake_map_calibrator/package.xml @@ -2,7 +2,7 @@ autoware_accel_brake_map_calibrator - 0.39.0 + 0.40.0 The accel_brake_map_calibrator Tomoya Kimura Taiki Tanaka diff --git a/vehicle/autoware_external_cmd_converter/CHANGELOG.rst b/vehicle/autoware_external_cmd_converter/CHANGELOG.rst index 7c1df55f31c03..ddbd655a9c34f 100644 --- a/vehicle/autoware_external_cmd_converter/CHANGELOG.rst +++ b/vehicle/autoware_external_cmd_converter/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_external_cmd_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - vehicle (`#9575 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/vehicle/autoware_external_cmd_converter/package.xml b/vehicle/autoware_external_cmd_converter/package.xml index 146327e6ca4b4..eb44058775a3f 100644 --- a/vehicle/autoware_external_cmd_converter/package.xml +++ b/vehicle/autoware_external_cmd_converter/package.xml @@ -2,7 +2,7 @@ autoware_external_cmd_converter - 0.39.0 + 0.40.0 The autoware_external_cmd_converter package Takamasa Horibe Eiki Nagata diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst b/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst index 5c9572a7b712d..de088bb8d5a76 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst +++ b/vehicle/autoware_raw_vehicle_cmd_converter/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_raw_vehicle_cmd_converter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* fix(cpplint): include what you use - vehicle (`#9575 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml index 1e3b265127a63..468e039312520 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/package.xml +++ b/vehicle/autoware_raw_vehicle_cmd_converter/package.xml @@ -2,7 +2,7 @@ autoware_raw_vehicle_cmd_converter - 0.39.0 + 0.40.0 The autoware_raw_vehicle_cmd_converter package Takamasa Horibe Tanaka Taiki diff --git a/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst b/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst index 8838f8de5c5d5..4e4f9c1a39a66 100644 --- a/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst +++ b/vehicle/autoware_steer_offset_estimator/CHANGELOG.rst @@ -2,6 +2,32 @@ Changelog for package autoware_steer_offset_estimator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* chore(package.xml): bump version to 0.39.0 (`#9587 `_) + * chore(package.xml): bump version to 0.39.0 + * fix: fix ticket links in CHANGELOG.rst + * fix: remove unnecessary diff + --------- + Co-authored-by: Yutaka Kondo +* fix: fix ticket links in CHANGELOG.rst (`#9588 `_) +* refactor(global_parameter_loader): prefix package and namespace with autoware (`#9303 `_) +* 0.39.0 +* update changelog +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) +* chore(package.xml): bump version to 0.38.0 (`#9266 `_) (`#9284 `_) + * unify package.xml version to 0.37.0 + * remove system_monitor/CHANGELOG.rst + * add changelog + * 0.38.0 + --------- +* Contributors: Esteve Fernandez, Fumiya Watanabe, Ryohsuke Mitsudome, Yutaka Kondo + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/vehicle/autoware_steer_offset_estimator/package.xml b/vehicle/autoware_steer_offset_estimator/package.xml index e3e633562b98a..715d80504dafe 100644 --- a/vehicle/autoware_steer_offset_estimator/package.xml +++ b/vehicle/autoware_steer_offset_estimator/package.xml @@ -1,7 +1,7 @@ autoware_steer_offset_estimator - 0.39.0 + 0.40.0 The steer_offset_estimator Taiki Tanaka Apache License 2.0 diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst index 7fdc075553c07..91b2ce31af3bf 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst +++ b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_mission_details_overlay_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml index 1ae744322766e..82b4c10194131 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml +++ b/visualization/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_mission_details_overlay_rviz_plugin - 0.39.0 + 0.40.0 RViz2 plugin for 2D overlays for mission details in the 3D view. Mainly a port of the JSK overlay plugin (https://github.com/jsk-ros-pkg/jsk_visualization). diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst index b1cef0c598a85..44c9901bda3ec 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_overlay_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml index 1a626d90bc02b..86bab15660d4d 100644 --- a/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml +++ b/visualization/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_overlay_rviz_plugin - 0.39.0 + 0.40.0 RViz2 plugin for 2D overlays in the 3D view. Mainly a port of the JSK overlay plugin (https://github.com/jsk-ros-pkg/jsk_visualization). diff --git a/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst b/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst index c84cd5bf35fa8..a1b325e441fc0 100644 --- a/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst +++ b/visualization/autoware_perception_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package autoware_perception_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/visualization/autoware_perception_rviz_plugin/package.xml b/visualization/autoware_perception_rviz_plugin/package.xml index 3f6c168c9857a..b3d2d69a34f35 100644 --- a/visualization/autoware_perception_rviz_plugin/package.xml +++ b/visualization/autoware_perception_rviz_plugin/package.xml @@ -2,7 +2,7 @@ autoware_perception_rviz_plugin - 0.39.0 + 0.40.0 Contains plugins to visualize object detection outputs Apex.AI, Inc. Taiki Tanaka diff --git a/visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst b/visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst index af35aa6921956..df222e8eb584e 100644 --- a/visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst +++ b/visualization/bag_time_manager_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package bag_time_manager_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/visualization/bag_time_manager_rviz_plugin/package.xml b/visualization/bag_time_manager_rviz_plugin/package.xml index c3e9895805a12..365dad286d22c 100644 --- a/visualization/bag_time_manager_rviz_plugin/package.xml +++ b/visualization/bag_time_manager_rviz_plugin/package.xml @@ -2,7 +2,7 @@ bag_time_manager_rviz_plugin - 0.39.0 + 0.40.0 Rviz plugin to publish and control the ros bag Taiki Tanaka Apache License 2.0 diff --git a/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst b/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst index ed05abec453cb..32c8d0a621304 100644 --- a/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_adapi_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_adapi_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/visualization/tier4_adapi_rviz_plugin/package.xml b/visualization/tier4_adapi_rviz_plugin/package.xml index 97418c7308f5b..da1af7b150c70 100644 --- a/visualization/tier4_adapi_rviz_plugin/package.xml +++ b/visualization/tier4_adapi_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_adapi_rviz_plugin - 0.39.0 + 0.40.0 The autoware adapi rviz plugin package Takagi, Isamu Hiroki OTA diff --git a/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst b/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst index 78b243eedcd85..99d51e3064524 100644 --- a/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_camera_view_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_camera_view_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/visualization/tier4_camera_view_rviz_plugin/package.xml b/visualization/tier4_camera_view_rviz_plugin/package.xml index 0728391e2e1ed..b25aac8a74570 100644 --- a/visualization/tier4_camera_view_rviz_plugin/package.xml +++ b/visualization/tier4_camera_view_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_camera_view_rviz_plugin - 0.39.0 + 0.40.0 The autoware camera view rviz plugin package Yuxuan Liu Makoto Yabuta diff --git a/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst b/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst index e5e5a9df7ec7f..155d36c369d77 100644 --- a/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_datetime_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_datetime_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/visualization/tier4_datetime_rviz_plugin/package.xml b/visualization/tier4_datetime_rviz_plugin/package.xml index 0a78d7408e3a3..80c19ec0957fd 100644 --- a/visualization/tier4_datetime_rviz_plugin/package.xml +++ b/visualization/tier4_datetime_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_datetime_rviz_plugin - 0.39.0 + 0.40.0 The tier4_datetime_rviz_plugin package Takagi, Isamu Apache License 2.0 diff --git a/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst b/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst index ddbe7b587d9e8..4e9985286862b 100644 --- a/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_localization_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_localization_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/visualization/tier4_localization_rviz_plugin/package.xml b/visualization/tier4_localization_rviz_plugin/package.xml index e5623a25416c2..e3f200aeb7111 100644 --- a/visualization/tier4_localization_rviz_plugin/package.xml +++ b/visualization/tier4_localization_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_localization_rviz_plugin - 0.39.0 + 0.40.0 The tier4_localization_rviz_plugin package Takagi, Isamu Takamasa Horibe diff --git a/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst b/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst index f6ddb9a16283a..8faac0b6ac8e7 100644 --- a/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_planning_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_planning_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/visualization/tier4_planning_rviz_plugin/package.xml b/visualization/tier4_planning_rviz_plugin/package.xml index 16dedcb450814..d615878f91354 100644 --- a/visualization/tier4_planning_rviz_plugin/package.xml +++ b/visualization/tier4_planning_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_planning_rviz_plugin - 0.39.0 + 0.40.0 The tier4_planning_rviz_plugin package Yukihiro Saito Takayuki Murooka diff --git a/visualization/tier4_state_rviz_plugin/CHANGELOG.rst b/visualization/tier4_state_rviz_plugin/CHANGELOG.rst index ac4988a0bff22..243d3c28733d7 100644 --- a/visualization/tier4_state_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_state_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_state_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/visualization/tier4_state_rviz_plugin/package.xml b/visualization/tier4_state_rviz_plugin/package.xml index 19c8c153b89ee..f5f5fa8b9c0c1 100644 --- a/visualization/tier4_state_rviz_plugin/package.xml +++ b/visualization/tier4_state_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_state_rviz_plugin - 0.39.0 + 0.40.0 The autoware state rviz plugin package Hiroki OTA Takagi, Isamu diff --git a/visualization/tier4_system_rviz_plugin/CHANGELOG.rst b/visualization/tier4_system_rviz_plugin/CHANGELOG.rst index f5895ae43b3db..a895b7135e0c8 100644 --- a/visualization/tier4_system_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_system_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_system_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/visualization/tier4_system_rviz_plugin/package.xml b/visualization/tier4_system_rviz_plugin/package.xml index 5e6a30689505f..5b768aa077120 100644 --- a/visualization/tier4_system_rviz_plugin/package.xml +++ b/visualization/tier4_system_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_system_rviz_plugin - 0.39.0 + 0.40.0 The tier4_vehicle_rviz_plugin package Koji Minoda Apache License 2.0 diff --git a/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst b/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst index 46c123392b23e..72e4ec068910b 100644 --- a/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_traffic_light_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_traffic_light_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * fix: fix ticket links to point to https://github.com/autowarefoundation/autoware.universe (`#9304 `_) diff --git a/visualization/tier4_traffic_light_rviz_plugin/package.xml b/visualization/tier4_traffic_light_rviz_plugin/package.xml index 6b8718488953a..b6645782290c1 100644 --- a/visualization/tier4_traffic_light_rviz_plugin/package.xml +++ b/visualization/tier4_traffic_light_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_traffic_light_rviz_plugin - 0.39.0 + 0.40.0 The autoware state rviz plugin package Satoshi OTA Apache License 2.0 diff --git a/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst b/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst index 33c59d1d1c93f..45d81a4646466 100644 --- a/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst +++ b/visualization/tier4_vehicle_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,14 @@ Changelog for package tier4_vehicle_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.40.0 (2024-12-12) +------------------- +* Merge branch 'main' into release-0.40.0 +* Revert "chore(package.xml): bump version to 0.39.0 (`#9587 `_)" + This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5. +* chore: move rviz plugins from common to visualization/ folder (`#9417 `_) +* Contributors: Esteve Fernandez, Fumiya Watanabe + 0.39.0 (2024-11-25) ------------------- * Merge commit '6a1ddbd08bd' into release-0.39.0 diff --git a/visualization/tier4_vehicle_rviz_plugin/package.xml b/visualization/tier4_vehicle_rviz_plugin/package.xml index 0aee4396e6167..4124ed2d514a3 100644 --- a/visualization/tier4_vehicle_rviz_plugin/package.xml +++ b/visualization/tier4_vehicle_rviz_plugin/package.xml @@ -2,7 +2,7 @@ tier4_vehicle_rviz_plugin - 0.39.0 + 0.40.0 The tier4_vehicle_rviz_plugin package Yukihiro Saito Apache License 2.0 From 1ae3eaf8546245bd6807eebbc87aacfe161baebe Mon Sep 17 00:00:00 2001 From: "tomoya.kimura" Date: Wed, 27 Nov 2024 17:28:07 +0900 Subject: [PATCH 273/273] chore: rename codeowners file Signed-off-by: tomoya.kimura --- .github/{CODEOWNERS => _CODEOWNERS} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename .github/{CODEOWNERS => _CODEOWNERS} (100%) diff --git a/.github/CODEOWNERS b/.github/_CODEOWNERS similarity index 100% rename from .github/CODEOWNERS rename to .github/_CODEOWNERS