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.
inlanecruising_plugin_node.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 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 <carma_planning_msgs/msg/plugin.hpp>
20#include <carma_ros2_utils/carma_lifecycle_node.hpp>
23#include <functional>
26#include <carma_planning_msgs/msg/trajectory_plan.hpp>
27#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
28#include <carma_planning_msgs/msg/plugin.hpp>
29#include <carma_planning_msgs/srv/plan_trajectory.hpp>
30#include <carma_debug_ros2_msgs/msg/trajectory_curvature_speeds.hpp>
31
33{
38{
39public:
40
44 explicit InLaneCruisingPluginNode(const rclcpp::NodeOptions &);
45
47 // Overrides
49 carma_ros2_utils::CallbackReturn on_configure_plugin();
50
51 bool get_availability() override;
52
53 std::string get_version_id() override final;
54
55 rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
56
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) override;
61
62private:
63
64 // Node configuration
66
67 std::string plugin_name_;
68 std::string version_id_;
69
70 carma_ros2_utils::PubPtr<carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds> trajectory_debug_pub_;
71
72 // Service Clients
73 carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory> yield_client_;
74
75 // Worker
76 std::shared_ptr<InLaneCruisingPlugin> worker_;
77
78 // Unit Test Accessors
79 FRIEND_TEST(InLaneCruisingPluginTest, rostest1);
80
81};
82
83} // namespace inlanecruising_plugin
TacticalPlugin base class which can be extended by user provided plugins which wish to implement the ...
carma_ros2_utils::ClientPtr< carma_planning_msgs::srv::PlanTrajectory > yield_client_
FRIEND_TEST(InLaneCruisingPluginTest, rostest1)
std::string get_version_id() override final
Returns the version id of this plugin.
carma_ros2_utils::CallbackReturn on_configure_plugin()
Method which is triggered when this plugin is moved from the UNCONFIGURED to INACTIVE states....
carma_ros2_utils::PubPtr< carma_debug_ros2_msgs::msg::TrajectoryCurvatureSpeeds > trajectory_debug_pub_
InLaneCruisingPluginNode(const rclcpp::NodeOptions &)
Node constructor.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
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 > srv_header, 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 InLaneCruisingPlugin.