Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
helper_functions.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2021-2024 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include <algorithm>
19
20
21namespace basic_autonomy
22{
23namespace waypoint_generation
24{
25 int get_nearest_point_index(const std::vector<lanelet::BasicPoint2d>& points,
26 const carma_planning_msgs::msg::VehicleState& state)
27 {
28 lanelet::BasicPoint2d veh_point(state.x_pos_global, state.y_pos_global);
29 double min_distance = std::numeric_limits<double>::max();
30 int i = 0;
31 int best_index = 0;
32 for (const auto& p : points)
33 {
34 double distance = lanelet::geometry::distance2d(p, veh_point);
35 if (distance < min_distance)
36 {
37 best_index = i;
38 min_distance = distance;
39 }
40 i++;
41 }
42 return best_index;
43 }
44
45 int get_nearest_point_index(const std::vector<PointSpeedPair>& points,
46 const carma_planning_msgs::msg::VehicleState& state)
47 {
48 lanelet::BasicPoint2d veh_point(state.x_pos_global, state.y_pos_global);
49 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(BASIC_AUTONOMY_LOGGER), "veh_point: " << veh_point.x() << ", " << veh_point.y());
50 double min_distance = std::numeric_limits<double>::max();
51 int i = 0;
52 int best_index = 0;
53 for (const auto& p : points)
54 {
55 double distance = lanelet::geometry::distance2d(p.point, veh_point);
56 if (distance < min_distance)
57 {
58 best_index = i;
59 min_distance = distance;
60 }
61 i++;
62 }
63 return best_index;
64 }
65
66 int get_nearest_index_by_downtrack(const std::vector<lanelet::BasicPoint2d>& points, const carma_wm::WorldModelConstPtr& wm, double target_downtrack)
67 {
68 if(std::empty(points)){
69 RCLCPP_WARN_STREAM(rclcpp::get_logger(BASIC_AUTONOMY_LOGGER), "Empty points vector received, returning -1");
70 return -1;
71 }
72
73 // Find first point with a downtrack greater than target_downtrack
74 const auto itr = std::find_if(std::cbegin(points), std::cend(points),
75 [&wm = std::as_const(wm), target_downtrack](const auto & point) { return wm->routeTrackPos(point).downtrack > target_downtrack; });
76
77 int best_index = std::size(points) - 1;
78
79 // Set best_index to the last point with a downtrack less than target_downtrack
80 if(itr != std::cbegin(points)){
81 best_index = std::distance(std::cbegin(points), std::prev(itr));
82 }
83 else{
84 best_index = 0;
85 }
86
87 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(BASIC_AUTONOMY_LOGGER), "get_nearest_index_by_downtrack>> Found best_index: " << best_index<<", points[i].x(): " << points.at(best_index).x() << ", points[i].y(): " << points.at(best_index).y());
88
89 return best_index;
90 }
91
92 void split_point_speed_pairs(const std::vector<PointSpeedPair>& points,
93 std::vector<lanelet::BasicPoint2d>* basic_points,
94 std::vector<double>* speeds)
95 {
96 basic_points->reserve(points.size());
97 speeds->reserve(points.size());
98
99 for (const auto& p : points)
100 {
101 basic_points->push_back(p.point);
102 speeds->push_back(p.speed);
103 }
104 }
105
106 int get_nearest_index_by_downtrack(const std::vector<PointSpeedPair>& points, const carma_wm::WorldModelConstPtr& wm,
107 const carma_planning_msgs::msg::VehicleState& state)
108 {
109 lanelet::BasicPoint2d state_pos(state.x_pos_global, state.y_pos_global);
110 double ending_downtrack = wm->routeTrackPos(state_pos).downtrack;
111 std::vector<lanelet::BasicPoint2d> basic_points;
112 std::vector<double> speeds;
113 split_point_speed_pairs(points, &basic_points, &speeds);
114 return get_nearest_index_by_downtrack(basic_points, wm, ending_downtrack);
115 }
116
117 int get_nearest_index_by_downtrack(const std::vector<lanelet::BasicPoint2d>& points, const carma_wm::WorldModelConstPtr& wm,
118 const carma_planning_msgs::msg::VehicleState& state)
119 {
120 lanelet::BasicPoint2d state_pos(state.x_pos_global, state.y_pos_global);
121 double ending_downtrack = wm->routeTrackPos(state_pos).downtrack;
122 return get_nearest_index_by_downtrack(points, wm, ending_downtrack);
123 }
124
125} // namespace waypoint_generation
126} // namespace basic_autonomy
void split_point_speed_pairs(const std::vector< PointSpeedPair > &points, std::vector< lanelet::BasicPoint2d > *basic_points, std::vector< double > *speeds)
Helper method to split a list of PointSpeedPair into separate point and speed lists.
static const std::string BASIC_AUTONOMY_LOGGER
int get_nearest_point_index(const std::vector< lanelet::BasicPoint2d > &points, const carma_planning_msgs::msg::VehicleState &state)
Returns the nearest point (in terms of cartesian 2d distance) to the provided vehicle pose in the pro...
int get_nearest_index_by_downtrack(const std::vector< lanelet::BasicPoint2d > &points, const carma_wm::WorldModelConstPtr &wm, double target_downtrack)
Returns the nearest "less than" point to the provided vehicle pose in the provided list by utilizing ...
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452