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_config.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2024 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 <iostream>
20#include <vector>
21
22namespace platooning_control
23{
24
29 {
30 double stand_still_headway_m = 12.0; // Standstill gap between vehicles (m)
31 double max_accel_mps2 = 2.5; // Maximum acceleration absolute value used in controller filters (m/s^2)
32 double kp = 0.5; // Proportional weight for PID controller
33 double kd = -0.5; // Derivative Weight for PID controller
34 double ki = 0.0; // Integral weight for PID controller
35 double max_delta_speed_per_timestep = 2; // Max value to restrict speed adjustment at one time step (limit on delta_v) (m/s)
36 double min_delta_speed_per_timestep = -10; // Min value to restrict speed adjustment at one time step (limit on delta_v) (m/s)
37
38 double adjustment_cap_mps = 10; // Adjustment cap for speed command (m/s)
39 int cmd_timestamp_ms = 100; // Timestamp to calculate ctrl commands (ms)
40 double integrator_max = 100; // Max limit for integrator term
41 double integrator_min = -100; // Max limit for integrator term
42 std::string vehicle_id = "DEFAULT_VEHICLE_ID"; // Vehicle id is the license plate of the vehicle
43 int shutdown_timeout = 200; // Timeout to stop generating ctrl signals after stopped receiving trajectory (ms)
44 int ignore_initial_inputs = 0; // num inputs to throw away after startup
45
46 //Pure Pursuit configs
47 double vehicle_response_lag = 0.2; // An approximation of the delay (sec) between sent vehicle commands and the vehicle begining a meaningful acceleration to that command
48 double max_lookahead_dist = 100.0;
49 double min_lookahead_dist = 6.0; // Min lookahead distance (m)
50 double speed_to_lookahead_ratio = 2.0; // Ratio to calculate lookahead distance
52 bool is_delay_compensation = true; // not to be confused with vehicle_response_lag, which is applied nonetheless
56
57 double dt = 0.1; // Timestep to calculate ctrl commands (s)
58 double integrator_max_pp = 0.0; //Max integrator val for pure pursuit integral controller
59 double integrator_min_pp = 0.0; //Min integrator val for pure pursuit integral controller
60 double ki_pp = 0.0; // Integral weight for pure pursuit integral controller";
64
65
66
67 // Stream operator for this config
68 friend std::ostream& operator<<(std::ostream& output, const PlatooningControlPluginConfig& c)
69 {
70 output << "PlatooningControlPluginConfig { " << std::endl
71 << "stand_still_headway_m: " << c.stand_still_headway_m << std::endl
72 << "max_accel_mps2: " << c.max_accel_mps2 << std::endl
73 << "kp: " << c.kp << std::endl
74 << "kd: " << c.kd << std::endl
75 << "ki: " << c.ki << std::endl
76 << "max_delta_speed_per_timestep: " << c.max_delta_speed_per_timestep << std::endl
77 << "min_delta_speed_per_timestep_: " << c.min_delta_speed_per_timestep << std::endl
78 << "adjustment_cap_mps: " << c.adjustment_cap_mps << std::endl
79 << "cmd_timestamp_ms: " << c.cmd_timestamp_ms << std::endl
80 << "integrator_max: " << c.integrator_max << std::endl
81 << "integrator_min: " << c.integrator_min << std::endl
82 << "vehicle_id: " << c.vehicle_id << std::endl
83 << "shutdown_timeout: " << c.shutdown_timeout << std::endl
84 << "ignore_initial_inputs: " << c.ignore_initial_inputs << std::endl
85 //Pure Pursuit configs
86 << "vehicle_response_lag" << c.vehicle_response_lag << std::endl
87 << "max_lookahead_dist: " << c.max_lookahead_dist << std::endl
88 << "min_lookahead_dist: " << c.min_lookahead_dist << std::endl
89 << "speed_to_lookahead_ratio: " << c.speed_to_lookahead_ratio << std::endl
90 << "is_interpolate_lookahead_point: " << c.is_interpolate_lookahead_point << std::endl
91 << "is_delay_compensation: " << c.is_delay_compensation << std::endl
92 << "emergency_stop_distance: " << c.emergency_stop_distance << std::endl
93 << "speed_thres_traveling_direction: "<< c.speed_thres_traveling_direction << std::endl
94 << "dist_front_rear_wheels: " << c.dist_front_rear_wheels << std::endl
95 << "dt: " << c.dt << std::endl
96 << "integrator_max_pp: " << c.integrator_max_pp << std::endl
97 << "integrator_min_pp: " << c.integrator_min_pp << std::endl
98 << "ki_pp_: " << c.ki_pp << std::endl
99 << "is_integrator_enabled" << c.is_integrator_enabled <<std::endl
100 << "enable_max_adjustment_filter" << c.enable_max_adjustment_filter << std::endl
101 << "enable_max_accel_filter" << c.enable_max_accel_filter << std::endl
102 << "}" << std::endl;
103 return output;
104 }
105};
106
107} // platooning_control
Stuct containing the algorithm configuration values for the PlatooningControlPlugin.
friend std::ostream & operator<<(std::ostream &output, const PlatooningControlPluginConfig &c)