20#include <carma_planning_msgs/msg/trajectory_plan.hpp>
21#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
22#include <carma_planning_msgs/msg/plugin.hpp>
24#include <boost/shared_ptr.hpp>
25#include <boost/geometry.hpp>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
28#include <carma_planning_msgs/srv/plan_trajectory.hpp>
32#include <unordered_set>
33#include <autoware_msgs/msg/lane.hpp>
34#include <rclcpp/rclcpp.hpp>
35#include <carma_planning_msgs/msg/maneuver.hpp>
39#include <gtest/gtest_prod.h>
47#define GET_MANEUVER_PROPERTY(mvr, property)\
48 (((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_LEFT_TURN ? (mvr).intersection_transit_left_turn_maneuver.property :\
49 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_RIGHT_TURN ? (mvr).intersection_transit_right_turn_maneuver.property :\
50 ((mvr).type == carma_planning_msgs::msg::Maneuver::INTERSECTION_TRANSIT_STRAIGHT ? (mvr).intersection_transit_straight_maneuver.property :\
51 ((mvr).type == carma_planning_msgs::msg::Maneuver::LANE_FOLLOWING ? (mvr).lane_following_maneuver.property :\
52 throw std::invalid_argument("GET_MANEUVER_PROPERTY (property) called on maneuver with invalid type id " + std::to_string((mvr).type)))))))
80 std::vector<PointSpeedPair>
maneuvers_to_points(
const std::vector<carma_planning_msgs::msg::Maneuver>& maneuvers,
82 const carma_planning_msgs::msg::VehicleState& state);
97 std::vector<lanelet::BasicPoint2d>& route_geometry_points,
double starting_speed,
const carma_planning_msgs::msg::VehicleState& states);
113 std::vector<lanelet::BasicPoint2d>& route_geometry_points,
double starting_speed);
129 std::vector<lanelet::BasicPoint2d>& route_geometry_points,
double starting_speed);
142 const std::vector<PointSpeedPair>& points,
const carma_planning_msgs::msg::VehicleState& state,
const rclcpp::Time& state_time);
148 rcl_interfaces::msg::SetParametersResult
151 std::shared_ptr<rmw_request_id_t>,
152 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
153 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
override;
TacticalPlugin base class which can be extended by user provided plugins which wish to implement the ...
Class containing primary business logic for the Stop Controlled Intersection Tactical Plugin.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
std::string stop_controlled_intersection_strategy_
bool get_availability()
Get the availability status of this plugin based on the current operating environment....
carma_wm::WorldModelConstPtr wm_
StopControlledIntersectionTacticalPlugin(const rclcpp::NodeOptions &options)
FRIEND_TEST(StopControlledIntersectionTacticalPlugin, TestSCIPlanning_case_one)
StopControlledIntersectionTacticalPluginConfig config_
std::vector< PointSpeedPair > maneuvers_to_points(const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers, const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::VehicleState &state)
Converts a set of requested stop controlled intersection maneuvers to point speed limit pairs.
FRIEND_TEST(StopControlledIntersectionTacticalPlugin, TestSCIPlanning_case_two)
std::vector< PointSpeedPair > create_case_two_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed)
Creates a speed profile according to case two of the stop controlled intersection,...
void plan_trajectory_callback(std::shared_ptr< rmw_request_id_t >, carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) override
Extending class provided callback which should return a planned trajectory based on the provided traj...
FRIEND_TEST(StopControlledIntersectionTacticalPlugin, TestSCIPlanning_case_three)
carma_ros2_utils::CallbackReturn on_configure_plugin() override
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....
std::string get_version_id()
Returns the version id of this plugin.
std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > compose_trajectory_from_centerline(const std::vector< PointSpeedPair > &points, const carma_planning_msgs::msg::VehicleState &state, const rclcpp::Time &state_time)
Method converts a list of lanelet centerline points and current vehicle state into a usable list of t...
std::vector< PointSpeedPair > create_case_one_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed, const carma_planning_msgs::msg::VehicleState &states)
Creates a speed profile according to case one of the stop controlled intersection,...
std::vector< PointSpeedPair > create_case_three_speed_profile(const carma_wm::WorldModelConstPtr &wm, const carma_planning_msgs::msg::Maneuver &maneuver, std::vector< lanelet::BasicPoint2d > &route_geometry_points, double starting_speed)
Creates a speed profile according to case three of the stop controlled intersection,...
std::shared_ptr< const WorldModel > WorldModelConstPtr
basic_autonomy::waypoint_generation::PointSpeedPair PointSpeedPair
Stuct containing the algorithm configuration values for the StopControlledIntersectionTacticalPlugin.