19#include <rclcpp/rclcpp.hpp>
38 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory>
yield_client_;
41 std::shared_ptr<LightControlledIntersectionTacticalPlugin>
worker_;
53 rcl_interfaces::msg::SetParametersResult
60 std::shared_ptr<rmw_request_id_t>,
61 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
62 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 LightControlledIntersectionTransitPluginNode.
LightControlledIntersectionTransitPluginNode(const rclcpp::NodeOptions &)
LightControlledIntersectionTransitPluginNode constructor.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Callback for dynamic parameter updates.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
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...
std::string get_version_id() override
Returns the version id of this plugin.
std::shared_ptr< LightControlledIntersectionTacticalPlugin > worker_
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.
Stuct containing the algorithm configuration values for light_controlled_intersection_tactical_plugin...