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.
plan_delegator.hpp
Go to the documentation of this file.
1#pragma once
2/*
3 * Copyright (C) 2022-2023 LEIDOS.
4 *
5 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
6 * use this file except in compliance with the License. You may obtain a copy of
7 * the License at
8 *
9 * http://www.apache.org/licenses/LICENSE-2.0
10 *
11 * Unless required by applicable law or agreed to in writing, software
12 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
13 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
14 * License for the specific language governing permissions and limitations under
15 * the License.
16 */
17
18#include <unordered_map>
19#include <math.h>
20#include <rclcpp/rclcpp.hpp>
21#include <gtest/gtest_prod.h>
22#include <carma_planning_msgs/msg/maneuver_plan.hpp>
23#include <carma_planning_msgs/msg/guidance_state.hpp>
24#include <carma_planning_msgs/msg/upcoming_lane_change_status.hpp>
25#include <carma_planning_msgs/srv/plan_trajectory.hpp>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
27#include <geometry_msgs/msg/pose_stamped.hpp>
28#include <geometry_msgs/msg/twist_stamped.hpp>
29#include <autoware_msgs/msg/lamp_cmd.hpp>
30#include <tf2_ros/transform_listener.h>
31#include <tf2/LinearMath/Transform.h>
32#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
35#include <carma_wm/Geometry.hpp>
36#include <string>
37
38// TODO Replace this Macro if possible
45#define GET_MANEUVER_PROPERTY(mvr, property)\
46 (((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN ? (mvr).intersection_transit_left_turn_maneuver.property :\
47 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ? (mvr).intersection_transit_right_turn_maneuver.property :\
48 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT ? (mvr).intersection_transit_straight_maneuver.property :\
49 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_CHANGE ? (mvr).lane_change_maneuver.property :\
50 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property :\
51 ((mvr).type == carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT ? (mvr).stop_and_wait_maneuver.property :\
52 throw new std::invalid_argument("GET_MANEUVER_PROPERTY (property) called on maneuver with invalid type id"))))))))
53
54
55#define SET_MANEUVER_PROPERTY(mvr, property, value)\
56 (((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN ? (mvr).intersection_transit_left_turn_maneuver.property = (value) :\
57 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ? (mvr).intersection_transit_right_turn_maneuver.property = (value) :\
58 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT ? (mvr).intersection_transit_straight_maneuver.property = (value) :\
59 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_CHANGE ? (mvr).lane_change_maneuver.property = (value) :\
60 ((mvr).type == carma_planning_msgs::msg::Maneuver::STOP_AND_WAIT ? (mvr).stop_and_wait_maneuver.property = (value) :\
61 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property = (value) :\
62 throw std::invalid_argument("ADJUST_MANEUVER_PROPERTY (property) called on maneuver with invalid type id " + std::to_string((mvr).type)))))))))
63
64
66{
70 struct Config
71 {
72 // ROS params
73 std::string planning_topic_prefix = "/plugins/";
74 std::string planning_topic_suffix = "/plan_trajectory";
77 double min_crawl_speed = 2.2352; // Min crawl speed in m/s
78 double duration_to_signal_before_lane_change = 2.5; // (Seconds) If an upcoming lane change will begin in under this time threshold, a turn signal activation command will be published.
79 int tactical_plugin_service_call_timeout = 100; // (Milliseconds) The maximum duration that Plan Delegator will wait after calling a tactical plugin's trajectory planning service; if trajectory
80 // generation takes longer than this, then planning will immediately end for the current trajectory planning iteration.
81
82 // Stream operator for this config
83 friend std::ostream &operator<<(std::ostream &output, const Config &c)
84 {
85 output << "PlanDelegator::Config { " << std::endl
86 << "planning_topic_prefix: " << c.planning_topic_prefix << std::endl
87 << "planning_topic_suffix: " << c.planning_topic_suffix << std::endl
88 << "trajectory_planning_rate: " << c.trajectory_planning_rate << std::endl
89 << "max_trajectory_duration: " << c.max_trajectory_duration << std::endl
90 << "min_crawl_speed: " << c.min_crawl_speed << std::endl
91 << "duration_to_signal_before_lane_change: " << c.duration_to_signal_before_lane_change << std::endl
92 << "}" << std::endl;
93 return output;
94 }
95 };
96
101 {
102 double starting_downtrack; // The starting downtrack of the lane change
103 bool is_right_lane_change; // Flag to indicate whether lane change is a right lane change; false if it is a left lane change
104 };
105
106 class PlanDelegator : public carma_ros2_utils::CarmaLifecycleNode
107 {
108 public:
109
110 // constants definition
111 static const constexpr double MILLISECOND_TO_SECOND = 0.001;
112
116 explicit PlanDelegator(const rclcpp::NodeOptions &);
117
121 void maneuverPlanCallback(carma_planning_msgs::msg::ManeuverPlan::UniquePtr plan);
122
126 void guidanceStateCallback(carma_planning_msgs::msg::GuidanceState::UniquePtr plan);
127
133 void poseCallback(geometry_msgs::msg::PoseStamped::UniquePtr pose_msg);
134
140 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> getPlannerClientByName(const std::string& planner_name);
141
147 bool isManeuverExpired(const carma_planning_msgs::msg::Maneuver& maneuver, rclcpp::Time current_time) const;
148
153 std::shared_ptr<carma_planning_msgs::srv::PlanTrajectory::Request> composePlanTrajectoryRequest(const carma_planning_msgs::msg::TrajectoryPlan& latest_trajectory_plan, const uint16_t& current_maneuver_index) const;
154
159
166 void updateManeuverParameters(carma_planning_msgs::msg::Maneuver& maneuver);
167
169 // Overrides
171 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
172 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &);
173
174 protected:
175 // Node configuration
177
178 // map to store service clients
179 std::unordered_map<std::string, carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory>> trajectory_planners_;
180 // local storage of incoming messages
181 carma_planning_msgs::msg::ManeuverPlan latest_maneuver_plan_;
182 geometry_msgs::msg::PoseStamped latest_pose_;
183 geometry_msgs::msg::TwistStamped latest_twist_;
184
185 // wm listener pointer and pointer to the actual wm object
188
189 private:
190 // ROS Publishers
191 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::TrajectoryPlan> traj_pub_;
192 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::UpcomingLaneChangeStatus> upcoming_lane_change_status_pub_;
193 carma_ros2_utils::PubPtr<autoware_msgs::msg::LampCmd> turn_signal_command_pub_;
194
195 // ROS Subscribers
196 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::ManeuverPlan> plan_sub_;
197 carma_ros2_utils::SubPtr<geometry_msgs::msg::PoseStamped> pose_sub_;
198 carma_ros2_utils::SubPtr<geometry_msgs::msg::TwistStamped> twist_sub_;
199 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> guidance_state_sub_;
200
201 rclcpp::TimerBase::SharedPtr traj_timer_;
202
203 bool guidance_engaged = false;
204
206
207 // TF listenser
208 tf2_ros::Buffer tf2_buffer_;
209 std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
210
211 // Object to store information regarding the next upcoming lane change in latest_maneuver_plan_; empty if no upcoming lane change exists in latest_maneuver_plan_
212 boost::optional<LaneChangeInformation> upcoming_lane_change_information_;
213
214 // Object to store information regarding the current active lane change in latest_maneuver_plan_; empty if first maneuver in latest_maneuver_plan_ is not a lane change
215 boost::optional<LaneChangeInformation> current_lane_change_information_;
216
217 // The latest UpcomingLaneChangeStatus that was published to upcoming_lane_change_status_pub_.
218 carma_planning_msgs::msg::UpcomingLaneChangeStatus upcoming_lane_change_status_;
219
220 // The latest turn signal command published to turn_signal_command_pub_.
221 autoware_msgs::msg::LampCmd latest_turn_signal_command_;
222
226 void onTrajPlanTick();
227
232 bool isManeuverPlanValid(const carma_planning_msgs::msg::ManeuverPlan& maneuver_plan) const noexcept;
233
238 bool isTrajectoryValid(const carma_planning_msgs::msg::TrajectoryPlan& trajectory_plan) const noexcept;
239
244 bool isTrajectoryLongEnough(const carma_planning_msgs::msg::TrajectoryPlan& plan) const noexcept;
245
250 carma_planning_msgs::msg::TrajectoryPlan planTrajectory();
251
257 LaneChangeInformation getLaneChangeInformation(const carma_planning_msgs::msg::Maneuver& lane_change_maneuver);
258
265 void publishUpcomingLaneChangeStatus(const boost::optional<LaneChangeInformation>& upcoming_lane_change_information);
266
279 void publishTurnSignalCommand(const boost::optional<LaneChangeInformation>& current_lane_change_information, const carma_planning_msgs::msg::UpcomingLaneChangeStatus& upcoming_lane_change_status);
280
281 // Unit Test Accessors
282 FRIEND_TEST(TestPlanDelegator, UnitTestPlanDelegator);
283 FRIEND_TEST(TestPlanDelegator, TestPlanDelegator);
284 FRIEND_TEST(TestPlanDelegator, TestLaneChangeInformation);
285 FRIEND_TEST(TestPlanDelegator, TestUpcomingLaneChangeAndTurnSignals);
286 FRIEND_TEST(TestPlanDelegator, TestUpdateManeuverParameters);
287 };
288}
Class which provies automated subscription and threading support for the world model.
Definition: WMListener.hpp:47
void onTrajPlanTick()
Callback function for triggering trajectory planning.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
carma_planning_msgs::msg::TrajectoryPlan planTrajectory()
Plan trajectory based on latest maneuver plan via ROS service call to plugins.
LaneChangeInformation getLaneChangeInformation(const carma_planning_msgs::msg::Maneuver &lane_change_maneuver)
Function for generating a LaneChangeInformation object from a provided lane change maneuver.
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > getPlannerClientByName(const std::string &planner_name)
Get PlanTrajectory service client by plugin name and create new PlanTrajectory service client if spec...
void poseCallback(geometry_msgs::msg::PoseStamped::UniquePtr pose_msg)
Callback function for vehicle pose subscriber. Updates latest_pose_ and makes calls to publishUpcomin...
carma_wm::WorldModelConstPtr wm_
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > twist_sub_
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
boost::optional< LaneChangeInformation > upcoming_lane_change_information_
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::UpcomingLaneChangeStatus > upcoming_lane_change_status_pub_
carma_planning_msgs::msg::UpcomingLaneChangeStatus upcoming_lane_change_status_
bool isTrajectoryValid(const carma_planning_msgs::msg::TrajectoryPlan &trajectory_plan) const noexcept
Example if a trajectory plan contains at least two trajectory points.
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
std::shared_ptr< carma_planning_msgs::srv::PlanTrajectory::Request > composePlanTrajectoryRequest(const carma_planning_msgs::msg::TrajectoryPlan &latest_trajectory_plan, const uint16_t &current_maneuver_index) const
Generate new PlanTrajecory service request based on current planning progress.
bool isManeuverExpired(const carma_planning_msgs::msg::Maneuver &maneuver, rclcpp::Time current_time) const
Example if a maneuver end time has passed current system time.
void guidanceStateCallback(carma_planning_msgs::msg::GuidanceState::UniquePtr plan)
Callback function of guidance state subscriber.
void updateManeuverParameters(carma_planning_msgs::msg::Maneuver &maneuver)
Update the starting downtrack, ending downtrack, and maneuver-specific Lanelet ID parameters associat...
rclcpp::TimerBase::SharedPtr traj_timer_
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::ManeuverPlan > plan_sub_
bool isTrajectoryLongEnough(const carma_planning_msgs::msg::TrajectoryPlan &plan) const noexcept
Example if a trajectory plan is longer than configured time thresheld.
carma_planning_msgs::msg::ManeuverPlan latest_maneuver_plan_
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::TrajectoryPlan > traj_pub_
carma_ros2_utils::PubPtr< autoware_msgs::msg::LampCmd > turn_signal_command_pub_
std::unique_ptr< tf2_ros::TransformListener > tf2_listener_
FRIEND_TEST(TestPlanDelegator, TestUpdateManeuverParameters)
boost::optional< LaneChangeInformation > current_lane_change_information_
std::unordered_map< std::string, carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > > trajectory_planners_
bool isManeuverPlanValid(const carma_planning_msgs::msg::ManeuverPlan &maneuver_plan) const noexcept
Example if a maneuver plan contains at least one maneuver.
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > pose_sub_
static const constexpr double MILLISECOND_TO_SECOND
FRIEND_TEST(TestPlanDelegator, TestLaneChangeInformation)
geometry_msgs::msg::TwistStamped latest_twist_
FRIEND_TEST(TestPlanDelegator, UnitTestPlanDelegator)
FRIEND_TEST(TestPlanDelegator, TestPlanDelegator)
void lookupFrontBumperTransform()
Lookup transfrom from front bumper to base link.
geometry_msgs::msg::PoseStamped latest_pose_
PlanDelegator(const rclcpp::NodeOptions &)
PlanDelegator constructor.
void maneuverPlanCallback(carma_planning_msgs::msg::ManeuverPlan::UniquePtr plan)
Callback function of maneuver plan subscriber.
autoware_msgs::msg::LampCmd latest_turn_signal_command_
void publishTurnSignalCommand(const boost::optional< LaneChangeInformation > &current_lane_change_information, const carma_planning_msgs::msg::UpcomingLaneChangeStatus &upcoming_lane_change_status)
Function for processing an optional LaneChangeInformation object pertaining to the currently-occurrin...
void publishUpcomingLaneChangeStatus(const boost::optional< LaneChangeInformation > &upcoming_lane_change_information)
Function for processing an optional LaneChangeInformation object pertaining to an upcoming lane chang...
FRIEND_TEST(TestPlanDelegator, TestUpcomingLaneChangeAndTurnSignals)
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
friend std::ostream & operator<<(std::ostream &output, const Config &c)
std::string planning_topic_suffix
std::string planning_topic_prefix
double duration_to_signal_before_lane_change
Convenience struct for storing information regarding a lane change maneuver.