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.
route_following_plugin.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2019-2021 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <vector>
20#include <carma_planning_msgs/msg/plugin.hpp>
21#include <carma_ros2_utils/carma_lifecycle_node.hpp>
22#include <geometry_msgs/msg/pose_stamped.hpp>
23#include <geometry_msgs/msg/twist_stamped.hpp>
26#include <carma_planning_msgs/srv/plan_maneuvers.hpp>
27#include <carma_planning_msgs/msg/trajectory_plan.hpp>
28#include <gtest/gtest_prod.h>
29#include <tf2_ros/transform_listener.h>
30#include <tf2/LinearMath/Transform.h>
31#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
32#include <unordered_set>
35
42#define GET_MANEUVER_PROPERTY(mvr, property)\
43 (((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN ? (mvr).intersection_transit_left_turn_maneuver.property :\
44 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ? (mvr).intersection_transit_right_turn_maneuver.property :\
45 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT ? (mvr).intersection_transit_straight_maneuver.property :\
46 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_CHANGE ? (mvr).lane_change_maneuver.property :\
47 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property :\
48 ((mvr).type == carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT ? (mvr).stop_and_wait_maneuver.property :\
49 throw std::invalid_argument("GET_MANEUVER_PROPERTY (property) called on maneuver with invalid type id " + std::to_string((mvr).type)))))))))
50
51#define SET_MANEUVER_PROPERTY(mvr, property, value)\
52 (((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN ? (mvr).intersection_transit_left_turn_maneuver.property = (value) :\
53 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ? (mvr).intersection_transit_right_turn_maneuver.property = (value) :\
54 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT ? (mvr).intersection_transit_straight_maneuver.property = (value) :\
55 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_CHANGE ? (mvr).lane_change_maneuver.property = (value) :\
56 ((mvr).type == carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT ? (mvr).stop_and_wait_maneuver.property = (value) :\
57 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property = (value) :\
58 throw std::invalid_argument("SET_MANEUVER_PROPERTY (property) called on maneuver with invalid type id " + std::to_string((mvr).type)))))))))
59
61{
63 {
64 public:
65
69 explicit RouteFollowingPlugin(const rclcpp::NodeOptions &);
70
72 carma_ros2_utils::CallbackReturn on_configure_plugin();
73 carma_ros2_utils::CallbackReturn on_activate_plugin();
74
75 // wm listener pointer and pointer to the actual wm object
76 std::shared_ptr<carma_wm::WMListener> wml_;
78
79 bool get_availability();
80 std::string get_version_id();
81
82 private:
83
93 carma_planning_msgs::msg::Maneuver composeLaneFollowingManeuverMessage(double start_dist, double end_dist, double start_speed, double target_speed, const std::vector<lanelet::Id>& lane_ids) const;
94
106 carma_planning_msgs::msg::Maneuver composeLaneChangeManeuverMessage(double start_dist, double end_dist, double start_speed, double target_speed, lanelet::Id starting_lane_id,lanelet::Id ending_lane_id) const;
107
119 carma_planning_msgs::msg::Maneuver composeStopAndWaitManeuverMessage(double start_dist, double end_dist, double start_speed, lanelet::Id starting_lane_id, lanelet::Id ending_lane_id, double stopping_accel) const;
120
127 bool isLaneChangeNeeded(lanelet::routing::LaneletRelations relations, lanelet::Id target_id) const;
128
134 void setManeuverStartDist(carma_planning_msgs::msg::Maneuver& maneuver, double start_dist) const;
135
141 void updateTimeProgress(std::vector<carma_planning_msgs::msg::Maneuver>& maneuvers, rclcpp::Time start_time) const;
147 void updateStartingSpeed(carma_planning_msgs::msg::Maneuver& maneuver, double start_speed) const;
148
157 std::shared_ptr<rmw_request_id_t> srv_header,
158 carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
159 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp);
160
166 double findSpeedLimit(const lanelet::ConstLanelet& llt);
167
172 std::vector<carma_planning_msgs::msg::Maneuver> routeCb(const lanelet::routing::LaneletPath& route_shortest_path);
173
195 std::vector<carma_planning_msgs::msg::Maneuver> addStopAndWaitAtRouteEnd (
196 const std::vector<carma_planning_msgs::msg::Maneuver>& input_maneuvers,
197 double route_end_downtrack, double stopping_entry_speed, double stopping_logitudinal_accel,
198 double lateral_accel_limit, double min_maneuver_length
199 ) const;
200
211 bool maneuverWithBufferStartsAfterDowntrack(const carma_planning_msgs::msg::Maneuver& maneuver, double downtrack, double lateral_accel, double min_maneuver_length) const;
212
218 std::string getNewManeuverId() const;
219
226 void returnToShortestPath(const lanelet::ConstLanelet &current_lanelet);
227
228 //Subscribers
229 carma_ros2_utils::SubPtr<geometry_msgs::msg::TwistStamped> twist_sub_;
230 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::ManeuverPlan> current_maneuver_plan_sub_;
231
232 // unordered set of all the lanelet ids in shortest path
233 std::unordered_set<lanelet::Id> shortest_path_set_;
234
235 static constexpr double MAX_LANE_WIDTH = 3.70; // Maximum lane width of a US highway
236
237 // Node configuration
239
240 // Current vehicle forward speed
241 double current_speed_ = 0.0;
242
243 //Small constant to compare doubles against
244 double epsilon_ = 0.0001;
245
246 // Current vehicle pose in map
247 geometry_msgs::msg::PoseStamped pose_msg_;
248 lanelet::BasicPoint2d current_loc_;
249
250 // Currently executing maneuver plan from Arbitrator
251 carma_planning_msgs::msg::ManeuverPlan::UniquePtr current_maneuver_plan_;
252
253 //Queue of maneuver plans
254 std::vector<carma_planning_msgs::msg::Maneuver> latest_maneuver_plan_;
255
256 //Tactical plugin being used for planning lane change
257 std::string lane_change_plugin_ = "cooperative_lanechange";
258 std::string stop_and_wait_plugin_ = "stop_and_wait_plugin";
259
260 std::string planning_strategic_plugin_ = "route_following_plugin";
261 std::string lanefollow_planning_tactical_plugin_ = "inlanecruising_plugin";
262
263 // Timer used to update the front bumper pose
264 rclcpp::TimerBase::SharedPtr bumper_pose_timer_;
265
269 void bumper_pose_cb();
270
275 void twist_cb(geometry_msgs::msg::TwistStamped::UniquePtr msg);
276
283 void current_maneuver_plan_cb(carma_planning_msgs::msg::ManeuverPlan::UniquePtr msg);
284
291 rclcpp::Duration getManeuverDuration(carma_planning_msgs::msg::Maneuver &maneuver, double epsilon) const;
292
297
298 geometry_msgs::msg::TransformStamped tf_;
299
300 // front bumper transform
301 tf2::Stamped<tf2::Transform> frontbumper_transform_;
302
303 // TF listenser
304 tf2_ros::Buffer tf2_buffer_;
305 std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
306
307 //Unit Tests
308 FRIEND_TEST(RouteFollowingPluginTest, testComposeManeuverMessage);
309 FRIEND_TEST(RouteFollowingPluginTest, testIdentifyLaneChange);
310 FRIEND_TEST(RouteFollowingPlugin, TestAssociateSpeedLimit);
311 FRIEND_TEST(RouteFollowingPlugin, TestAssociateSpeedLimitusingosm);
312 FRIEND_TEST(RouteFollowingPlugin, TestHelperfunctions);
313 FRIEND_TEST(RouteFollowingPlugin, TestReturnToShortestPath);
314 FRIEND_TEST(StopAndWaitTestFixture, CaseOne);
315 FRIEND_TEST(StopAndWaitTestFixture, CaseTwo);
316 FRIEND_TEST(StopAndWaitTestFixture, CaseThree);
317 FRIEND_TEST(StopAndWaitTestFixture, CaseFour);
318 FRIEND_TEST(StopAndWaitTestFixture, CaseFive);
319 FRIEND_TEST(StopAndWaitTestFixture, CaseSix);
320 FRIEND_TEST(StopAndWaitTestFixture, CaseSeven);
321 FRIEND_TEST(StopAndWaitTestFixture, CaseEight);
322 FRIEND_TEST(StopAndWaitTestFixture, CaseNine);
323 FRIEND_TEST(StopAndWaitTestFixture, CaseTen);
324
325 };
326}
StrategicPlugin base class which can be extended by user provided plugins which wish to implement the...
FRIEND_TEST(RouteFollowingPlugin, TestReturnToShortestPath)
carma_ros2_utils::CallbackReturn on_configure_plugin()
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....
FRIEND_TEST(StopAndWaitTestFixture, CaseThree)
std::string get_version_id()
Returns the version id of this plugin.
FRIEND_TEST(StopAndWaitTestFixture, CaseSix)
void initializeBumperTransformLookup()
Initialize transform lookup from front bumper to map.
std::vector< carma_planning_msgs::msg::Maneuver > latest_maneuver_plan_
std::unordered_set< lanelet::Id > shortest_path_set_
FRIEND_TEST(RouteFollowingPlugin, TestHelperfunctions)
FRIEND_TEST(RouteFollowingPluginTest, testComposeManeuverMessage)
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
void updateTimeProgress(std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers, rclcpp::Time start_time) const
Given an array of maneuvers update the starting time for each.
carma_planning_msgs::msg::Maneuver composeLaneChangeManeuverMessage(double start_dist, double end_dist, double start_speed, double target_speed, lanelet::Id starting_lane_id, lanelet::Id ending_lane_id) const
Compose a lane change maneuver message based on input params NOTE: The start and stop time are not se...
std::string getNewManeuverId() const
This method returns a new UUID as a string for assignment to a Maneuver message.
FRIEND_TEST(RouteFollowingPlugin, TestAssociateSpeedLimit)
bool maneuverWithBufferStartsAfterDowntrack(const carma_planning_msgs::msg::Maneuver &maneuver, double downtrack, double lateral_accel, double min_maneuver_length) const
Identifies if a maneuver starts after the provided downtrack with compensation for a dynamic buffer s...
std::vector< carma_planning_msgs::msg::Maneuver > routeCb(const lanelet::routing::LaneletPath &route_shortest_path)
Calculate maneuver plan for remaining route. This callback is triggered when a new route has been rec...
FRIEND_TEST(StopAndWaitTestFixture, CaseSeven)
carma_planning_msgs::msg::Maneuver composeLaneFollowingManeuverMessage(double start_dist, double end_dist, double start_speed, double target_speed, const std::vector< lanelet::Id > &lane_ids) const
Compose a lane keeping maneuver message based on input params.
FRIEND_TEST(StopAndWaitTestFixture, CaseFour)
void setManeuverStartDist(carma_planning_msgs::msg::Maneuver &maneuver, double start_dist) const
Set the start distance of a maneuver based on the progress along the route.
carma_planning_msgs::msg::ManeuverPlan::UniquePtr current_maneuver_plan_
void bumper_pose_cb()
Callback for the front bumper pose transform.
void updateStartingSpeed(carma_planning_msgs::msg::Maneuver &maneuver, double start_speed) const
Given an maneuver update the starting speed.
FRIEND_TEST(StopAndWaitTestFixture, CaseTwo)
void current_maneuver_plan_cb(carma_planning_msgs::msg::ManeuverPlan::UniquePtr msg)
Callback for the ManeuverPlan subscriber, will store the current maneuver plan received locally....
void twist_cb(geometry_msgs::msg::TwistStamped::UniquePtr msg)
Callback for the twist subscriber, which will store latest twist locally.
void plan_maneuvers_callback(std::shared_ptr< rmw_request_id_t > srv_header, carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req, carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp)
Service callback for arbitrator maneuver planning.
double findSpeedLimit(const lanelet::ConstLanelet &llt)
Given a Lanelet, find it's associated Speed Limit.
bool isLaneChangeNeeded(lanelet::routing::LaneletRelations relations, lanelet::Id target_id) const
Given a LaneletRelations and ID of the next lanelet in the shortest path.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::ManeuverPlan > current_maneuver_plan_sub_
carma_ros2_utils::CallbackReturn on_activate_plugin()
Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states....
std::shared_ptr< carma_wm::WMListener > wml_
rclcpp::Duration getManeuverDuration(carma_planning_msgs::msg::Maneuver &maneuver, double epsilon) const
returns duration as ros::Duration required to complete maneuver given its start dist,...
FRIEND_TEST(StopAndWaitTestFixture, CaseEight)
void returnToShortestPath(const lanelet::ConstLanelet &current_lanelet)
This method re-routes the vehicle back to the shortest path, if the vehicle has left the shortest pat...
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > twist_sub_
RouteFollowingPlugin(const rclcpp::NodeOptions &)
Default constructor for RouteFollowingPlugin class.
FRIEND_TEST(StopAndWaitTestFixture, CaseFive)
carma_planning_msgs::msg::Maneuver composeStopAndWaitManeuverMessage(double start_dist, double end_dist, double start_speed, lanelet::Id starting_lane_id, lanelet::Id ending_lane_id, double stopping_accel) const
Compose a stop and wait maneuver message based on input params. NOTE: The start and stop time are not...
FRIEND_TEST(StopAndWaitTestFixture, CaseNine)
FRIEND_TEST(RouteFollowingPlugin, TestAssociateSpeedLimitusingosm)
std::vector< carma_planning_msgs::msg::Maneuver > addStopAndWaitAtRouteEnd(const std::vector< carma_planning_msgs::msg::Maneuver > &input_maneuvers, double route_end_downtrack, double stopping_entry_speed, double stopping_logitudinal_accel, double lateral_accel_limit, double min_maneuver_length) const
Adds a StopAndWait maneuver to the end of a maneuver set stopping at the provided downtrack value NOT...
bool get_availability()
Get the availability status of this plugin based on the current operating environment....
FRIEND_TEST(StopAndWaitTestFixture, CaseTen)
FRIEND_TEST(StopAndWaitTestFixture, CaseOne)
FRIEND_TEST(RouteFollowingPluginTest, testIdentifyLaneChange)
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
Struct containing config values values for route_following_plugin.