19#include <rclcpp/rclcpp.hpp>
23#include <boost/uuid/uuid_generators.hpp>
24#include <boost/uuid/uuid_io.hpp>
25#include <lanelet2_core/geometry/Point.h>
26#include <trajectory_utils/trajectory_utils.hpp>
27#include <trajectory_utils/conversions/conversions.hpp>
30#include <carma_ros2_utils/carma_lifecycle_node.hpp>
32#include <Eigen/Geometry>
35#include <unordered_set>
39#include <lanelet2_core/primitives/Lanelet.h>
40#include <lanelet2_core/geometry/LineString.h>
43#include <std_msgs/msg/float64.hpp>
44#include <carma_planning_msgs/msg/stop_and_wait_maneuver.hpp>
46#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
47#include <carma_planning_msgs/msg/trajectory_plan.hpp>
59 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory>
yield_client_;
82 rcl_interfaces::msg::SetParametersResult
90 std::shared_ptr<rmw_request_id_t> srv_header,
91 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
92 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 ...
std::shared_ptr< StopandWait > plugin_
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
void plan_trajectory_callback(std::shared_ptr< rmw_request_id_t > srv_header, 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...
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
std::string get_version_id() override final
Returns the version id of this plugin.
carma_ros2_utils::CallbackReturn on_configure_plugin()
This method should be used to load parameters and will be called on the configure state transition.
StopandWaitNode(const rclcpp::NodeOptions &)
Node constructor.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
StopandWaitConfig config_
Stuct containing the algorithm configuration values for the stop_and_wait_plugin.