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.cpp
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 */
17
18namespace platooning_control
19{
20 namespace std_ph = std::placeholders;
21
22 PlatooningControlPlugin::PlatooningControlPlugin(const rclcpp::NodeOptions &options)
23 : carma_guidance_plugins::ControlPlugin(options), config_(PlatooningControlPluginConfig()), pcw_(PlatooningControlWorker())
24 {
25
26 // Declare parameters
27 config_.stand_still_headway_m = declare_parameter<double>("stand_still_headway_m", config_.stand_still_headway_m);
28 config_.max_accel_mps2 = declare_parameter<double>("max_accel_mps2", config_.max_accel_mps2);
29 config_.kp = declare_parameter<double>("kp", config_.kp);
30 config_.kd = declare_parameter<double>("kd", config_.kd);
31 config_.ki = declare_parameter<double>("ki", config_.ki);
32 config_.max_delta_speed_per_timestep = declare_parameter<double>("max_delta_speed_per_timestep", config_.max_delta_speed_per_timestep);
33 config_.min_delta_speed_per_timestep = declare_parameter<double>("min_delta_speed_per_timestep", config_.min_delta_speed_per_timestep);
34 config_.adjustment_cap_mps = declare_parameter<double>("adjustment_cap_mps", config_.adjustment_cap_mps);
35 config_.cmd_timestamp_ms = declare_parameter<int>("cmd_timestamp_ms", config_.cmd_timestamp_ms);
36 config_.integrator_max = declare_parameter<double>("integrator_max", config_.integrator_max);
37 config_.integrator_min = declare_parameter<double>("integrator_min", config_.integrator_min);
38
39 config_.vehicle_response_lag = declare_parameter<double>("vehicle_response_lag", config_.vehicle_response_lag);
40 config_.max_lookahead_dist = declare_parameter<double>("maximum_lookahead_distance", config_.max_lookahead_dist);
41 config_.min_lookahead_dist = declare_parameter<double>("minimum_lookahead_distance", config_.min_lookahead_dist);
42 config_.speed_to_lookahead_ratio = declare_parameter<double>("speed_to_lookahead_ratio", config_.speed_to_lookahead_ratio);
43 config_.is_interpolate_lookahead_point = declare_parameter<bool>("is_interpolate_lookahead_point", config_.is_interpolate_lookahead_point);
44 config_.is_delay_compensation = declare_parameter<bool>("is_delay_compensation", config_.is_delay_compensation);
45 config_.emergency_stop_distance = declare_parameter<double>("emergency_stop_distance", config_.emergency_stop_distance);
46 config_.speed_thres_traveling_direction = declare_parameter<double>("speed_thres_traveling_direction", config_.speed_thres_traveling_direction);
47 config_.dist_front_rear_wheels = declare_parameter<double>("dist_front_rear_wheels", config_.dist_front_rear_wheels);
48
49 config_.dt = declare_parameter<double>("dt", config_.dt);
50 config_.integrator_max_pp = declare_parameter<double>("integrator_max_pp", config_.integrator_max_pp);
51 config_.integrator_min_pp = declare_parameter<double>("integrator_min_pp", config_.integrator_min_pp);
52 config_.ki_pp = declare_parameter<double>("Ki_pp", config_.ki_pp);
53 config_.is_integrator_enabled = declare_parameter<bool>("is_integrator_enabled", config_.is_integrator_enabled);
54 config_.enable_max_adjustment_filter = declare_parameter<bool>("enable_max_adjustment_filter", config_.enable_max_adjustment_filter);
55 config_.enable_max_accel_filter = declare_parameter<bool>("enable_max_accel_filter", config_.enable_max_accel_filter);
56
57 //Global params (from vehicle config)
58 config_.vehicle_id = declare_parameter<std::string>("vehicle_id", config_.vehicle_id);
59 config_.shutdown_timeout = declare_parameter<int>("control_plugin_shutdown_timeout", config_.shutdown_timeout);
60 config_.ignore_initial_inputs = declare_parameter<int>("control_plugin_ignore_initial_inputs", config_.ignore_initial_inputs);
61
62 pcw_.ctrl_config_ = std::make_shared<PlatooningControlPluginConfig>(config_);
63
64 }
65
66 rcl_interfaces::msg::SetParametersResult PlatooningControlPlugin::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
67 {
68 auto error_double = update_params<double>({
69 {"stand_still_headway_m", config_.stand_still_headway_m},
70 {"max_accel_mps2", config_.max_accel_mps2},
71 {"kp", config_.kp},
72 {"kd", config_.kd},
73 {"ki", config_.ki},
74 {"max_delta_speed_per_timestep", config_.max_delta_speed_per_timestep},
75 {"min_delta_speed_per_timestep", config_.min_delta_speed_per_timestep},
76 {"adjustment_cap_mps", config_.adjustment_cap_mps},
77 {"integrator_max", config_.integrator_max},
78 {"integrator_min", config_.integrator_min},
79
80 {"vehicle_response_lag", config_.vehicle_response_lag},
81 {"max_lookahead_dist", config_.max_lookahead_dist},
82 {"min_lookahead_dist", config_.min_lookahead_dist},
83 {"speed_to_lookahead_ratio", config_.speed_to_lookahead_ratio},
84 {"emergency_stop_distance",config_.emergency_stop_distance},
85 {"speed_thres_traveling_direction", config_.speed_thres_traveling_direction},
86 {"dist_front_rear_wheels", config_.dist_front_rear_wheels},
87 {"dt", config_.dt},
88 {"integrator_max_pp", config_.integrator_max_pp},
89 {"integrator_min_pp", config_.integrator_min_pp},
90 {"Ki_pp", config_.ki_pp},
91 }, parameters);
92
93 auto error_int = update_params<int>({
94 {"cmd_timestamp_ms", config_.cmd_timestamp_ms},
95 }, parameters);
96
97 auto error_bool = update_params<bool>({
98 {"is_interpolate_lookahead_point", config_.is_interpolate_lookahead_point},
99 {"is_delay_compensation",config_.is_delay_compensation},
100 {"is_integrator_enabled", config_.is_integrator_enabled},
101 {"enable_max_adjustment_filter", config_.enable_max_adjustment_filter},
102 {"enable_max_accel_filter", config_.enable_max_accel_filter},
103 }, parameters);
104
105 // vehicle_id, control_plugin_shutdown_timeout and control_plugin_ignore_initial_inputs are not updated as they are global params
106 rcl_interfaces::msg::SetParametersResult result;
107
108 result.successful = !error_double && !error_int && !error_bool;
109
110 return result;
111
112 }
113
114 carma_ros2_utils::CallbackReturn PlatooningControlPlugin::on_configure_plugin()
115 {
116 // Reset config
118
119 // Load parameters
120 get_parameter<double>("stand_still_headway_m", config_.stand_still_headway_m);
121 get_parameter<double>("max_accel_mps2", config_.max_accel_mps2);
122 get_parameter<double>("kp", config_.kp);
123 get_parameter<double>("kd", config_.kd);
124 get_parameter<double>("ki", config_.ki);
125 get_parameter<double>("max_delta_speed_per_timestep", config_.max_delta_speed_per_timestep);
126 get_parameter<double>("min_delta_speed_per_timestep", config_.min_delta_speed_per_timestep);
127 get_parameter<double>("adjustment_cap_mps", config_.adjustment_cap_mps);
128 get_parameter<int>("cmd_timestamp_ms", config_.cmd_timestamp_ms);
129 get_parameter<double>("integrator_max", config_.integrator_max);
130 get_parameter<double>("integrator_min", config_.integrator_min);
131
132 get_parameter<std::string>("vehicle_id", config_.vehicle_id);
133 get_parameter<int>("control_plugin_shutdown_timeout", config_.shutdown_timeout);
134 get_parameter<int>("control_plugin_ignore_initial_inputs", config_.ignore_initial_inputs);
135 get_parameter<bool>("enable_max_adjustment_filter", config_.enable_max_adjustment_filter);
136 get_parameter<bool>("enable_max_accel_filter", config_.enable_max_accel_filter);
137
138 //Pure Pursuit params
139 get_parameter<double>("vehicle_response_lag", config_.vehicle_response_lag);
140 get_parameter<double>("maximum_lookahead_distance", config_.max_lookahead_dist);
141 get_parameter<double>("minimum_lookahead_distance", config_.min_lookahead_dist);
142 get_parameter<double>("speed_to_lookahead_ratio", config_.speed_to_lookahead_ratio);
143 get_parameter<bool>("is_interpolate_lookahead_point", config_.is_interpolate_lookahead_point);
144 get_parameter<bool>("is_delay_compensation", config_.is_delay_compensation);
145 get_parameter<double>("emergency_stop_distance", config_.emergency_stop_distance);
146 get_parameter<double>("speed_thres_traveling_direction", config_.speed_thres_traveling_direction);
147 get_parameter<double>("dist_front_rear_wheels", config_.dist_front_rear_wheels);
148
149 get_parameter<double>("dt", config_.dt);
150 get_parameter<double>("integrator_max_pp", config_.integrator_max_pp);
151 get_parameter<double>("integrator_min_pp", config_.integrator_min_pp);
152 get_parameter<double>("Ki_pp", config_.ki_pp);
153 get_parameter<bool>("is_integrator_enabled", config_.is_integrator_enabled);
154
155
156 RCLCPP_INFO_STREAM(rclcpp::get_logger("platooning_control"), "Loaded Params: " << config_);
157
158 // create config for pure_pursuit worker
159 pure_pursuit::Config cfg{
168 };
169
170 pure_pursuit::IntegratorConfig i_cfg;
171 i_cfg.dt = config_.dt;
172 i_cfg.integrator_max_pp = config_.integrator_max_pp;
173 i_cfg.integrator_min_pp = config_.integrator_min_pp;
174 i_cfg.Ki_pp = config_.ki_pp;
175 i_cfg.integral = 0.0; // accumulator of integral starts from 0
176 i_cfg.is_integrator_enabled = config_.is_integrator_enabled;
177
178 pp_ = std::make_shared<pure_pursuit::PurePursuit>(cfg, i_cfg);
179
180 // Register runtime parameter update callback
181 add_on_set_parameters_callback(std::bind(&PlatooningControlPlugin::parameter_update_callback, this, std_ph::_1));
182
183
184 // Trajectory Plan Subscriber
185 trajectory_plan_sub_ = create_subscription<carma_planning_msgs::msg::TrajectoryPlan>("platooning_control/plan_trajectory", 1,
186 std::bind(&PlatooningControlPlugin::current_trajectory_callback, this, std_ph::_1));
187
188 // Platoon Info Subscriber
189 platoon_info_sub_ = create_subscription<carma_planning_msgs::msg::PlatooningInfo>("platoon_info", 1, std::bind(&PlatooningControlPlugin::platoon_info_cb, this, std_ph::_1));
190
191
192 //Control Publishers
193 platoon_info_pub_ = create_publisher<carma_planning_msgs::msg::PlatooningInfo>("platooning_info", 1);
194
195
196 // Return success if everthing initialized successfully
197 return CallbackReturn::SUCCESS;
198 }
199
200
201 autoware_msgs::msg::ControlCommandStamped PlatooningControlPlugin::generate_command()
202 {
203
204 autoware_msgs::msg::ControlCommandStamped ctrl_msg;
206 return ctrl_msg;
207
208 // If it has been a long time since input data has arrived then reset the input counter and return
209 // Note: this quiets the controller after its input stream stops, which is necessary to allow
210 // the replacement controller to publish on the same output topic after this one is done.
211 double current_time_ms = this->now().nanoseconds() / 1e6;
212 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "current_time_ms = " << current_time_ms << ", prev_input_time_ms_ = " << prev_input_time_ms_ << ", input counter = " << consecutive_input_counter_);
213
214 if(current_time_ms - prev_input_time_ms_ > config_.shutdown_timeout)
215 {
216 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "returning due to timeout.");
218 return ctrl_msg;
219 }
220
221 // If there have not been enough consecutive timely inputs then return (waiting for
222 // previous control plugin to time out and stop publishing, since it uses same output topic)
224 {
225 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "returning due to first data input");
226 return ctrl_msg;
227 }
228
229 carma_planning_msgs::msg::TrajectoryPlanPoint second_trajectory_point = current_trajectory_.get().trajectory_points[1];
230
232
233 ctrl_msg = generate_control_signals(second_trajectory_point, current_pose_.get(), current_twist_.get());
234
235 return ctrl_msg;
236
237 }
238
239 void PlatooningControlPlugin::platoon_info_cb(const carma_planning_msgs::msg::PlatooningInfo::SharedPtr msg)
240 {
241
242 platoon_leader_.staticId = msg->leader_id;
243 platoon_leader_.vehiclePosition = msg->leader_downtrack_distance;
244 platoon_leader_.commandSpeed = msg->leader_cmd_speed;
245 // TODO: index is 0 temp to test the leader state
246 platoon_leader_.NumberOfVehicleInFront = msg->host_platoon_position;
248
249 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "Platoon leader leader id: " << platoon_leader_.staticId);
250 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "Platoon leader leader pose: " << platoon_leader_.vehiclePosition);
251 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "Platoon leader leader cmd speed: " << platoon_leader_.commandSpeed);
252
253 carma_planning_msgs::msg::PlatooningInfo platooning_info_msg = *msg;
254
255 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "platooning_info_msg.actual_gap: " << platooning_info_msg.actual_gap);
256
257 if (platooning_info_msg.actual_gap > 5.0)
258 {
259 platooning_info_msg.actual_gap -= 5.0; // TODO: temporary: should be vehicle length
260 }
261
262 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "platooning_info_msg.actual_gap: " << platooning_info_msg.actual_gap);
263 // platooing_info_msg.desired_gap = pcw_.desired_gap_;
264 // platooing_info_msg.actual_gap = pcw_.actual_gap_;
265 pcw_.actual_gap_ = platooning_info_msg.actual_gap;
266 pcw_.desired_gap_ = platooning_info_msg.desired_gap;
267
268 platooning_info_msg.host_cmd_speed = pcw_.speedCmd_;
269 platoon_info_pub_->publish(platooning_info_msg);
270 }
271
272 autoware_msgs::msg::ControlCommandStamped PlatooningControlPlugin::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)
273 {
274 pcw_.set_current_speed(trajectory_speed_); //TODO why this and not the actual vehicle speed? Method name suggests different use than this.
275 // pcw_.set_current_speed(current_twist_.get());
277 pcw_.generate_speed(first_trajectory_point);
278
279 motion::control::controller_common::State state_tf = convert_state(current_pose, current_twist);
280 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "Forced from frame_id: " << state_tf.header.frame_id << ", into: " << current_trajectory_.get().header.frame_id);
281
282 current_trajectory_.get().header.frame_id = state_tf.header.frame_id;
283
285
286 pp_->set_trajectory(autoware_traj_plan);
287 const auto cmd{pp_->compute_command(state_tf)};
288
289 auto steer_cmd = cmd.front_wheel_angle_rad; //autoware sets the front wheel angle as the calculated steer. https://github.com/usdot-fhwa-stol/autoware.auto/blob/3450f94fa694f51b00de272d412722d65a2c2d3e/AutowareAuto/src/control/pure_pursuit/src/pure_pursuit.cpp#L88
290
291 autoware_msgs::msg::ControlCommandStamped ctrl_msg = compose_ctrl_cmd(pcw_.speedCmd_, steer_cmd);
292
293 return ctrl_msg;
294 }
295
296 motion::motion_common::State PlatooningControlPlugin::convert_state(const geometry_msgs::msg::PoseStamped& pose, const geometry_msgs::msg::TwistStamped& twist) const
297 {
298 motion::motion_common::State state;
299 state.header = pose.header;
300 state.state.x = pose.pose.position.x;
301 state.state.y = pose.pose.position.y;
302 state.state.z = pose.pose.position.z;
303 state.state.heading.real = pose.pose.orientation.w;
304 state.state.heading.imag = pose.pose.orientation.z;
305
306 state.state.longitudinal_velocity_mps = twist.twist.linear.x;
307 return state;
308 }
309
310 void PlatooningControlPlugin::current_trajectory_callback(const carma_planning_msgs::msg::TrajectoryPlan::UniquePtr tp)
311 {
312 if (tp->trajectory_points.size() < 2) {
313 RCLCPP_WARN_STREAM(rclcpp::get_logger("platooning_control"), "PlatooningControlPlugin cannot execute trajectory as only 1 point was provided");
314 return;
315 }
316
318 prev_input_time_ms_ = this->now().nanoseconds() / 1000000;
320 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "New trajectory plan #" << consecutive_input_counter_ << " at time " << prev_input_time_ms_);
321 rclcpp::Time tp_time(tp->header.stamp);
322 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "tp header time = " << tp_time.nanoseconds() / 1000000);
323 }
324
325 geometry_msgs::msg::TwistStamped PlatooningControlPlugin::compose_twist_cmd(double linear_vel, double angular_vel)
326 {
327 geometry_msgs::msg::TwistStamped cmd_twist;
328 cmd_twist.twist.linear.x = linear_vel;
329 cmd_twist.twist.angular.z = angular_vel;
330 cmd_twist.header.stamp = this->now();
331 return cmd_twist;
332 }
333
334 autoware_msgs::msg::ControlCommandStamped PlatooningControlPlugin::compose_ctrl_cmd(double linear_vel, double steering_angle)
335 {
336 autoware_msgs::msg::ControlCommandStamped cmd_ctrl;
337 cmd_ctrl.header.stamp = this->now();
338 cmd_ctrl.cmd.linear_velocity = linear_vel;
339 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "ctrl command speed " << cmd_ctrl.cmd.linear_velocity);
340 cmd_ctrl.cmd.steering_angle = steering_angle;
341 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "ctrl command steering " << cmd_ctrl.cmd.steering_angle);
342
343 return cmd_ctrl;
344 }
345
347 return true; // TODO for user implement actual check on availability if applicable to plugin
348 }
349
351 return "v1.0";
352 }
353
354 // extract maximum speed of trajectory
355 double PlatooningControlPlugin::get_trajectory_speed(const std::vector<carma_planning_msgs::msg::TrajectoryPlanPoint>& trajectory_points)
356 {
357 double trajectory_speed = 0;
358
359 double dx1 = trajectory_points[trajectory_points.size()-1].x - trajectory_points[0].x;
360 double dy1 = trajectory_points[trajectory_points.size()-1].y - trajectory_points[0].y;
361 double d1 = sqrt(dx1*dx1 + dy1*dy1);
362 double t1 = (rclcpp::Time((trajectory_points[trajectory_points.size()-1].target_time)).nanoseconds() - rclcpp::Time(trajectory_points[0].target_time).nanoseconds())/1e9;
363
364 double avg_speed = d1/t1;
365 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "trajectory_points size = " << trajectory_points.size() << ", d1 = " << d1 << ", t1 = " << t1 << ", avg_speed = " << avg_speed);
366
367 for(size_t i = 0; i < trajectory_points.size() - 2; i++ )
368 {
369 double dx = trajectory_points[i + 1].x - trajectory_points[i].x;
370 double dy = trajectory_points[i + 1].y - trajectory_points[i].y;
371 double d = sqrt(dx*dx + dy*dy);
372 double t = rclcpp::Time((trajectory_points[i + 1].target_time)).seconds() - rclcpp::Time(trajectory_points[i].target_time).seconds();
373 double v = d/t;
374 if(v > trajectory_speed)
375 {
376 trajectory_speed = v;
377 }
378 }
379
380 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "trajectory speed: " << trajectory_speed);
381 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platooning_control"), "avg trajectory speed: " << avg_speed);
382
383 return avg_speed; //TODO: why are 2 speeds being calculated? Which should be returned?
384
385 }
386
387
388} // platooning_control
389
390#include "rclcpp_components/register_node_macro.hpp"
391
392// Register the component with class_loader
393RCLCPP_COMPONENTS_REGISTER_NODE(platooning_control::PlatooningControlPlugin)
boost::optional< geometry_msgs::msg::TwistStamped > current_twist_
The most recent velocity message received by this node.
boost::optional< carma_planning_msgs::msg::TrajectoryPlan > current_trajectory_
The most recent trajectory received by this plugin.
boost::optional< geometry_msgs::msg::PoseStamped > current_pose_
The most recent pose message received by this node.
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.
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_
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...
void set_leader(const PlatoonLeaderInfo &leader)
Sets the platoon leader object using info from msg.
void set_current_speed(double speed)
set current speed
std::shared_ptr< PlatooningControlPluginConfig > ctrl_config_
void generate_speed(const carma_planning_msgs::msg::TrajectoryPlanPoint &point)
Generates speed commands (in m/s) based on the trajectory point.
autoware_auto_msgs::msg::Trajectory process_trajectory_plan(const carma_planning_msgs::msg::TrajectoryPlan &tp, double vehicle_response_lag)
Given a carma type of trajectory_plan, generate autoware type of trajectory accounting for speed_lag ...
Stuct containing the algorithm configuration values for the PlatooningControlPlugin.