19#include <rclcpp/rclcpp.hpp>
21#include <carma_planning_msgs/msg/plugin.hpp>
22#include <carma_ros2_utils/carma_lifecycle_node.hpp>
23#include <carma_planning_msgs/srv/plan_trajectory.hpp>
44 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory>
client_;
57 std::vector<carma_planning_msgs::msg::Maneuver>
convert_maneuver_plan(
const std::vector<carma_planning_msgs::msg::Maneuver>& maneuvers);
63 std::shared_ptr<rmw_request_id_t>,
64 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
65 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 ...
ROS node for the inlanecruising_plugin.
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > client_
std::vector< carma_planning_msgs::msg::Maneuver > converted_maneuvers_
std::vector< carma_planning_msgs::msg::Maneuver > convert_maneuver_plan(const std::vector< carma_planning_msgs::msg::Maneuver > &maneuvers)
Converts a sequence of INTERSECTION_TRANSIT maneuvers to LANE_FOLLOWING maneuvers.
IntersectionTransitManeuveringNode(const rclcpp::NodeOptions &)
IntersectionTransitManeuveringNode constructor.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
carma_ros2_utils::CallbackReturn on_configure_plugin() override
This method should be used to load parameters and will be called on the configure state transition.
std::shared_ptr< CallInterface > object_
std::string get_version_id() override
Returns the version id of this plugin.
carma_planning_msgs::msg::VehicleState vehicle_state_
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...