22 namespace std_ph = std::placeholders;
30 return "strategic_plan/plan_maneuvers";
35 return carma_planning_msgs::msg::Plugin::STRATEGIC;
41 plan_maneuvers_service_ = create_service<carma_planning_msgs::srv::PlanManeuvers>(std::string(get_name()) +
"/plan_maneuvers",
42 [
this] (
auto header,
auto req,
auto resp) {
PluginBaseNode provides default functionality for all carma guidance plugins. This includes basic sta...
virtual bool get_activation_status() final
Returns the activation status of this plugin. The plugins API callbacks will only be triggered when t...
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override final
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override final
std::string get_capability() override
Get the capability string representing this plugins capabilities Method must be overriden by extendin...
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override final
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override final
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override final
StrategicPlugin(const rclcpp::NodeOptions &)
StrategicPlugin constructor.
carma_ros2_utils::ServicePtr< carma_planning_msgs::srv::PlanManeuvers > plan_maneuvers_service_
The service which will be called when a strategic plugin needs to plan maneuvers.
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override final
virtual 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)=0
Extending class provided callback which should return a planned trajectory based on the provided traj...
uint8_t get_type() override final
Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum....