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.
platooning_tactical_plugin_node.h
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2019-2022 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <functional>
20#include <rclcpp/rclcpp.hpp>
24
25
27{
32 {
33 private:
35
36 std::shared_ptr<PlatooningTacticalPlugin> worker_;
37
38 public:
42 explicit Node(const rclcpp::NodeOptions &);
43
47 rcl_interfaces::msg::SetParametersResult
48 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
49
51 // Overrides
54 std::shared_ptr<rmw_request_id_t>,
55 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
56 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) override;
57
58 bool get_availability() override;
59
60 std::string get_version_id() override;
61
65 carma_ros2_utils::CallbackReturn on_configure_plugin();
66 };
67
68} // namespace platooning_tactical_plugin
TacticalPlugin base class which can be extended by user provided plugins which wish to implement the ...
ROS node for the PlatooningTacticalPlugin to initialize and configure parameters and publishers/subsc...
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Example callback for dynamic parameter updates.
std::shared_ptr< PlatooningTacticalPlugin > worker_
std::string get_version_id() override
Returns the version id of this plugin.
carma_ros2_utils::CallbackReturn on_configure_plugin()
This method should be used to load parameters and will be called on the configure state transition.
Node(const rclcpp::NodeOptions &)
Node constructor.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
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...
Stuct containing the algorithm configuration values for the PlatooningTacticalPlugin.