18#include <unordered_map>
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>
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"))))))))
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)))))))))
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
133 void poseCallback(geometry_msgs::msg::PoseStamped::UniquePtr pose_msg);
140 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory>
getPlannerClientByName(
const std::string& planner_name);
147 bool isManeuverExpired(
const carma_planning_msgs::msg::Maneuver& maneuver, rclcpp::Time current_time)
const;
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;
179 std::unordered_map<std::string, carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory>>
trajectory_planners_;
191 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::TrajectoryPlan>
traj_pub_;
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_;
232 bool isManeuverPlanValid(
const carma_planning_msgs::msg::ManeuverPlan& maneuver_plan)
const noexcept;
238 bool isTrajectoryValid(
const carma_planning_msgs::msg::TrajectoryPlan& trajectory_plan)
const noexcept;
279 void publishTurnSignalCommand(
const boost::optional<LaneChangeInformation>& current_lane_change_information,
const carma_planning_msgs::msg::UpcomingLaneChangeStatus& upcoming_lane_change_status);
285 FRIEND_TEST(TestPlanDelegator, TestUpcomingLaneChangeAndTurnSignals);
Class which provies automated subscription and threading support for the world model.
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_
tf2_ros::Buffer tf2_buffer_
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 ¤t_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_
double length_to_front_bumper_
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 > ¤t_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)
carma_wm::WMListener wml_
std::shared_ptr< const WorldModel > WorldModelConstPtr
double trajectory_planning_rate
friend std::ostream & operator<<(std::ostream &output, const Config &c)
std::string planning_topic_suffix
std::string planning_topic_prefix
int tactical_plugin_service_call_timeout
double duration_to_signal_before_lane_change
double max_trajectory_duration