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.
stop_controlled_intersection_plugin.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2022 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/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>
27#include <carma_wm/Geometry.hpp>
28#include <carma_planning_msgs/srv/plan_trajectory.hpp>
30#include <functional>
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>
40
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)))))))
53
55{
57
64{
65public:
66
67 // brief Constructor
68 explicit StopControlledIntersectionTacticalPlugin(const rclcpp::NodeOptions &options);
69
80 std::vector<PointSpeedPair> maneuvers_to_points(const std::vector<carma_planning_msgs::msg::Maneuver>& maneuvers,
82 const carma_planning_msgs::msg::VehicleState& state);
83
96 std::vector<PointSpeedPair> create_case_one_speed_profile(const carma_wm::WorldModelConstPtr& wm, const carma_planning_msgs::msg::Maneuver& maneuver,
97 std::vector<lanelet::BasicPoint2d>& route_geometry_points, double starting_speed, const carma_planning_msgs::msg::VehicleState& states);
98
112 std::vector<PointSpeedPair> create_case_two_speed_profile(const carma_wm::WorldModelConstPtr& wm, const carma_planning_msgs::msg::Maneuver& maneuver,
113 std::vector<lanelet::BasicPoint2d>& route_geometry_points, double starting_speed);
114
128 std::vector<PointSpeedPair> create_case_three_speed_profile(const carma_wm::WorldModelConstPtr& wm, const carma_planning_msgs::msg::Maneuver& maneuver,
129 std::vector<lanelet::BasicPoint2d>& route_geometry_points, double starting_speed);
130
141 std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint> compose_trajectory_from_centerline(
142 const std::vector<PointSpeedPair>& points, const carma_planning_msgs::msg::VehicleState& state, const rclcpp::Time& state_time);
143
144 // overrides
145 carma_ros2_utils::CallbackReturn on_configure_plugin() override;
146 bool get_availability();
147 std::string get_version_id();
148 rcl_interfaces::msg::SetParametersResult
149 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
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;
154
155 private:
156
159
160 std::string stop_controlled_intersection_strategy_ = "Carma/stop_controlled_intersection";
161
162 double epsilon_ = 0.001; //Small constant to compare (double) 0.0 with
163
164 // Unit Test Accessors
168};
169
170
171} // namespace stop_controlled_intersection_tactical_plugin
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 > &parameters)
bool get_availability()
Get the availability status of this plugin based on the current operating environment....
FRIEND_TEST(StopControlledIntersectionTacticalPlugin, TestSCIPlanning_case_one)
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::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
Definition: WorldModel.hpp:452
basic_autonomy::waypoint_generation::PointSpeedPair PointSpeedPair
Stuct containing the algorithm configuration values for the StopControlledIntersectionTacticalPlugin.