19#include <rclcpp/rclcpp.hpp>
21#include <carma_planning_msgs/srv/plan_maneuvers.hpp>
22#include <carma_planning_msgs/msg/plugin.hpp>
23#include <carma_planning_msgs/msg/guidance_state.hpp>
26#include <carma_ros2_utils/carma_lifecycle_node.hpp>
28#include <lanelet2_core/Forward.h>
29#include <gtest/gtest_prod.h>
30#include <boost/property_tree/ptree.hpp>
31#include <boost/property_tree/json_parser.hpp>
32#include <boost/algorithm/string/split.hpp>
33#include <boost/algorithm/string/classification.hpp>
67 std::shared_ptr<rmw_request_id_t> srv_header,
68 carma_planning_msgs::srv::PlanManeuvers::Request::SharedPtr req,
69 carma_planning_msgs::srv::PlanManeuvers::Response::SharedPtr resp);
74 rcl_interfaces::msg::SetParametersResult
81 void currentPoseCb(geometry_msgs::msg::PoseStamped::UniquePtr msg);
98 double target_speed, rclcpp::Time start_time,
double time_to_stop,
99 std::vector<lanelet::Id> lane_ids);
102 const lanelet::Id& starting_lane_id,
const lanelet::Id& ending_lane_id,
103 double stopping_accel, rclcpp::Time start_time, rclcpp::Time end_time)
const;
122 bool shortest_path_only =
false,
123 bool bounds_inclusive =
true)
const;
141 void guidance_state_cb(
const carma_planning_msgs::msg::GuidanceState::UniquePtr msg);
StrategicPlugin base class which can be extended by user provided plugins which wish to implement the...
FRIEND_TEST(StopAndDwellStrategicPluginTest, findSpeedLimit)
StopAndDwellStrategicPlugin(const rclcpp::NodeOptions &)
Default constructor for RouteFollowingPlugin class.
carma_planning_msgs::msg::Maneuver composeStopAndWaitManeuverMessage(double current_dist, double end_dist, double start_speed, const lanelet::Id &starting_lane_id, const lanelet::Id &ending_lane_id, double stopping_accel, rclcpp::Time start_time, rclcpp::Time end_time) const
void guidance_state_cb(const carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
Callback for the Guidance State.
carma_wm::WorldModelConstPtr wm_
World Model pointer.
std::string get_version_id()
Returns the version id of this plugin.
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) const
Given a Lanelet, find it's associated Speed Limit.
bool approaching_stop_controlled_interction_
carma_ros2_utils::CallbackReturn on_activate_plugin()
Method which is triggered when this plugin is moved from the INACTIVE to ACTIVE states....
VehicleState extractInitialState(const carma_planning_msgs::srv::PlanManeuvers::Request &req) const
Helper method to extract the initial vehicle state from the planning request method based on if the p...
double current_downtrack_
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > guidance_state_sub_
carma_ros2_utils::CallbackReturn on_configure_plugin()
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....
StopAndDwellStrategicPluginConfig config_
Config containing configurable algorithm parameters.
FRIEND_TEST(StopAndDwellStrategicPluginTest, maneuvercbtest)
bool get_availability()
Get the availability status of this plugin based on the current operating environment....
double bus_stop_downtrack_
carma_wm::WorldModelConstPtr get_wm()
std::vector< lanelet::ConstLanelet > getLaneletsBetweenWithException(double start_downtrack, double end_downtrack, bool shortest_path_only=false, bool bounds_inclusive=true) const
Helper method which calls carma_wm::WorldModel::getLaneletsBetween(start_downtrack,...
void currentPoseCb(geometry_msgs::msg::PoseStamped::UniquePtr msg)
callback function for current pose
double max_comfort_accel_
double max_comfort_decel_norm_
carma_planning_msgs::msg::Maneuver composeLaneFollowingManeuverMessage(double start_dist, double end_dist, double start_speed, double target_speed, rclcpp::Time start_time, double time_to_stop, std::vector< lanelet::Id > lane_ids)
Compose a lane keeping maneuver message based on input params.
rclcpp::Time time_to_move_
double max_comfort_decel_
void set_wm(carma_wm::WorldModelConstPtr new_wm)
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > current_pose_sub_
std::shared_ptr< const WorldModel > WorldModelConstPtr
Struct to store the configuration settings for the WzStrategicPlugin class.
Struct representing a vehicle state for the purposes of planning.