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.
tactical_plugin.hpp
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#pragma once
18
19#include <rclcpp/rclcpp.hpp>
20#include <carma_planning_msgs/srv/plan_trajectory.hpp>
21
23
25{
26
34 {
35
36 private:
37 // Services
39 carma_ros2_utils::ServicePtr<carma_planning_msgs::srv::PlanTrajectory> plan_trajectory_service_;
40
41 public:
45 explicit TacticalPlugin(const rclcpp::NodeOptions &);
46
48 virtual ~TacticalPlugin() = default;
49
58 std::shared_ptr<rmw_request_id_t> srv_header,
59 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
60 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) = 0;
61
62
64 // Overrides
66
67 // Non-Final to allow extending plugins to provide more detailed capabilities
68 std::string get_capability() override;
69
70 // Final
71 uint8_t get_type() override final;
72
73 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override final;
74 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override final;
75 carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override final;
76 carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override final;
77 carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override final;
78 carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override final;
79 };
80
81} // carma_guidance_plugins
PluginBaseNode provides default functionality for all carma guidance plugins. This includes basic sta...
TacticalPlugin base class which can be extended by user provided plugins which wish to implement the ...
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override final
uint8_t get_type() override final
Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum....
carma_ros2_utils::ServicePtr< carma_planning_msgs::srv::PlanTrajectory > plan_trajectory_service_
The ros service which can be called by the arbitrator or other plugins to have this plugin generate a...
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_cleanup(const rclcpp_lifecycle::State &) override final
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override final
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override final
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override final
virtual ~TacticalPlugin()=default
Virtual destructor for safe deletion.
virtual 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)=0
Extending class provided callback which should return a planned trajectory based on the provided traj...
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override final
TacticalPlugin(const rclcpp::NodeOptions &)
TacticalPlugin constructor.