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_control.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2024 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 <functional>
21#include <carma_planning_msgs/msg/trajectory_plan_point.hpp>
22#include <geometry_msgs/msg/twist_stamped.hpp>
23#include <autoware_msgs/msg/control_command.hpp>
24#include <carma_planning_msgs/msg/platooning_info.hpp>
25
29#include <pure_pursuit/pure_pursuit.hpp>
31#include <gtest/gtest_prod.h>
32
33namespace pure_pursuit = autoware::motion::control::pure_pursuit;
34namespace platooning_control
35{
36
42 {
43
44 public:
48 explicit PlatooningControlPlugin(const rclcpp::NodeOptions& options);
49
55 autoware_msgs::msg::ControlCommandStamped generate_control_signals(const carma_planning_msgs::msg::TrajectoryPlanPoint& first_trajectory_point, const geometry_msgs::msg::PoseStamped& current_pose, const geometry_msgs::msg::TwistStamped& current_twist);
56
63 geometry_msgs::msg::TwistStamped compose_twist_cmd(double linear_vel, double angular_vel);
64
65 motion::motion_common::State convert_state(const geometry_msgs::msg::PoseStamped& pose, const geometry_msgs::msg::TwistStamped& twist) const;
66
67 double trajectory_speed_ = 0.0;
68
72 rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
73
78 void current_trajectory_callback(const carma_planning_msgs::msg::TrajectoryPlan::UniquePtr tp);
79
86 autoware_msgs::msg::ControlCommandStamped compose_ctrl_cmd(double linear_vel, double steering_angle);
87
91 bool get_availability() override;
92
96 std::string get_version_id() override;
97
99 // Overrides
101
102 autoware_msgs::msg::ControlCommandStamped generate_command() override;
103
107 carma_ros2_utils::CallbackReturn on_configure_plugin() override;
108
109 std::shared_ptr<pure_pursuit::PurePursuit> pp_;
110
111
112 private:
113
114 // Node configuration
116
117 // platoon control worker object
119
120 // Variables
122 double prev_input_time_ms_ = 0; //timestamp of the previous trajectory plan input received
123 long consecutive_input_counter_ = 0; //num inputs seen without a timeout
124
129 void platoon_info_cb(const carma_planning_msgs::msg::PlatooningInfo::SharedPtr msg);
130
136 double get_trajectory_speed(const std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint>& trajectory_points);
137
138
139 // Subscribers
140 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::TrajectoryPlan> trajectory_plan_sub_;
141 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::PlatooningInfo> platoon_info_sub_;
142
143 // Publishers
144 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::PlatooningInfo> platoon_info_pub_;
145
146 // Unit Test Accessors
147 FRIEND_TEST(PlatooningControlPluginTest, test_platoon_info_cb);
148 FRIEND_TEST(PlatooningControlPluginTest, test_get_trajectory_speed);
149 FRIEND_TEST(PlatooningControlPluginTest, test_generate_controls);
150 FRIEND_TEST(PlatooningControlPluginTest, test_current_trajectory_callback);
151
152 };
153
154} // platooning_control
ControlPlugin base class which can be extended by user provided plugins which wish to implement the C...
This class includes node-level logic for Platooning Control such as its publishers,...
motion::motion_common::State convert_state(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped &twist) const
void platoon_info_cb(const carma_planning_msgs::msg::PlatooningInfo::SharedPtr msg)
callback function for platoon info
bool get_availability() override
Returns availability of plugin. Always true.
carma_ros2_utils::CallbackReturn on_configure_plugin() override
This method should be used to load parameters and will be called on the configure state transition.
void current_trajectory_callback(const carma_planning_msgs::msg::TrajectoryPlan::UniquePtr tp)
callback function for trajectory plan
double get_trajectory_speed(const std::vector< carma_planning_msgs::msg::TrajectoryPlanPoint > &trajectory_points)
calculate average speed of a set of trajectory points
geometry_msgs::msg::TwistStamped compose_twist_cmd(double linear_vel, double angular_vel)
Compose twist message from linear and angular velocity commands.
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Callback for dynamic parameter updates.
FRIEND_TEST(PlatooningControlPluginTest, test_get_trajectory_speed)
std::string get_version_id() override
Returns version id of plugn.
autoware_msgs::msg::ControlCommandStamped compose_ctrl_cmd(double linear_vel, double steering_angle)
Compose control message from speed and steering commands.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::PlatooningInfo > platoon_info_sub_
FRIEND_TEST(PlatooningControlPluginTest, test_generate_controls)
FRIEND_TEST(PlatooningControlPluginTest, test_platoon_info_cb)
FRIEND_TEST(PlatooningControlPluginTest, test_current_trajectory_callback)
autoware_msgs::msg::ControlCommandStamped generate_control_signals(const carma_planning_msgs::msg::TrajectoryPlanPoint &first_trajectory_point, const geometry_msgs::msg::PoseStamped &current_pose, const geometry_msgs::msg::TwistStamped &current_twist)
generate control signal by calculating speed and steering commands.
autoware_msgs::msg::ControlCommandStamped generate_command() override
Extending class provided method which should generate a command message which will be published to th...
std::shared_ptr< pure_pursuit::PurePursuit > pp_
carma_ros2_utils::PubPtr< carma_planning_msgs::msg::PlatooningInfo > platoon_info_pub_
PlatooningControlPlugin(const rclcpp::NodeOptions &options)
PlatooningControlPlugin constructor.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > trajectory_plan_sub_
This is the worker class for platoon controller. It is responsible for generating and smoothing the s...
Stuct containing the algorithm configuration values for the PlatooningControlPlugin.