Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
strategic_plugin.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#include <functional>
19
21{
22 namespace std_ph = std::placeholders;
23
24 StrategicPlugin::StrategicPlugin(const rclcpp::NodeOptions &options)
25 : PluginBaseNode(options)
26 {}
27
29 {
30 return "strategic_plan/plan_maneuvers";
31 }
32
34 {
35 return carma_planning_msgs::msg::Plugin::STRATEGIC;
36 }
37
38 carma_ros2_utils::CallbackReturn StrategicPlugin::handle_on_configure(const rclcpp_lifecycle::State &prev_state)
39 {
40 // Initialize plan maneuvers service
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) {
43 if (this->get_activation_status()) // Only trigger when activated
44 {
45 this->plan_maneuvers_callback(header, req, resp);
46 }
47 });
48
49 return PluginBaseNode::handle_on_configure(prev_state);
50 }
51
52 carma_ros2_utils::CallbackReturn StrategicPlugin::handle_on_activate(const rclcpp_lifecycle::State &prev_state)
53 {
54 return PluginBaseNode::handle_on_activate(prev_state);
55 }
56
57 carma_ros2_utils::CallbackReturn StrategicPlugin::handle_on_deactivate(const rclcpp_lifecycle::State &prev_state)
58 {
59 return PluginBaseNode::handle_on_deactivate(prev_state);
60 }
61
62 carma_ros2_utils::CallbackReturn StrategicPlugin::handle_on_cleanup(const rclcpp_lifecycle::State &prev_state)
63 {
64 return PluginBaseNode::handle_on_cleanup(prev_state);
65 }
66
67 carma_ros2_utils::CallbackReturn StrategicPlugin::handle_on_shutdown(const rclcpp_lifecycle::State &prev_state)
68 {
69 return PluginBaseNode::handle_on_shutdown(prev_state);
70 }
71
72 carma_ros2_utils::CallbackReturn StrategicPlugin::handle_on_error(const rclcpp_lifecycle::State &prev_state, const std::string &exception_string)
73 {
74 return PluginBaseNode::handle_on_error(prev_state, exception_string);
75 }
76
77} // carma_guidance_plugins
78
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....