From e15e69222430322e5504c6b2980b772dd633d9f7 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Wed, 22 Jan 2025 17:34:27 +0900 Subject: [PATCH] rm wrong file Signed-off-by: Maxime CLEMENT --- .../src/planner_data.cpp | 101 ------------------ 1 file changed, 101 deletions(-) delete mode 100644 planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/planner_data.cpp diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/planner_data.cpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/planner_data.cpp deleted file mode 100644 index 15e8d4019b5fb..0000000000000 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common_universe/src/planner_data.cpp +++ /dev/null @@ -1,101 +0,0 @@ -// Copyright 2024 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include -#include -#include - -#include - -namespace autoware::motion_velocity_planner -{ -std::optional PlannerData::get_traffic_signal( - 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)); -} - -std::optional PlannerData::calculate_min_deceleration_distance( - const double target_velocity) const -{ - return motion_utils::calcDecelDistWithJerkAndAccConstraints( - current_odometry.twist.twist.linear.x, target_velocity, - current_acceleration.accel.accel.linear.x, velocity_smoother_->getMinDecel(), - std::abs(velocity_smoother_->getMinJerk()), velocity_smoother_->getMinJerk()); -} - -std::vector calculate_stop_points( - const lanelet::Lanelet & lanelet, - const std::vector & trajectory, - const universe_utils::LineString2d & trajectory_ls, const double ego_longitudinal_offset) -{ - std::vector stop_points; - const auto stop_lines = lanelet::utils::query::stopLinesLanelet(lanelet); - for (const auto & stop_line : stop_lines) { - const auto stop_line_2d = lanelet::utils::to2D(stop_line).basicLineString(); - universe_utils::MultiPoint2d intersections; - boost::geometry::intersection(trajectory_ls, stop_line_2d, intersections); - for (const auto & intersection : intersections) { - const auto p = geometry_msgs::msg::Point().set__x(intersection.x()).set__y(intersection.y()); - const auto stop_line_arc_length = motion_utils::calcSignedArcLength(trajectory, 0UL, p); - StopPoint sp; - sp.ego_trajectory_arc_length = stop_line_arc_length - ego_longitudinal_offset; - if (sp.ego_trajectory_arc_length < 0.0) { - continue; - } - sp.stop_line = stop_line_2d; - sp.ego_stop_pose = - motion_utils::calcInterpolatedPose(trajectory, sp.ego_trajectory_arc_length); - stop_points.push_back(sp); - } - } - return stop_points; -} - -std::vector PlannerData::calculate_map_stop_points( - const std::vector & trajectory) const -{ - std::vector stop_points; - if (!route_handler) { - return stop_points; - } - universe_utils::LineString2d trajectory_ls; - for (const auto & p : trajectory) { - trajectory_ls.emplace_back(p.pose.position.x, p.pose.position.y); - } - const auto candidates = route_handler->getLaneletMapPtr()->laneletLayer.search( - boost::geometry::return_envelope(trajectory_ls)); - for (const auto & candidate : candidates) { - const auto points = calculate_stop_points( - candidate, trajectory, trajectory_ls, vehicle_info_.max_longitudinal_offset_m); - stop_points.insert(stop_points.end(), points.begin(), points.end()); - } - return stop_points; -} -} // namespace autoware::motion_velocity_planner