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; }