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.
platoon_config_ihp.h
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2021 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
22{
23
28{
29 // following parameters are for general platooning plugin
30 double vehicleLength = 5.0; // m
31 int maxPlatoonSize = 10; // 1
32 int algorithmType = 0; // N/A
33 int statusMessageInterval = 100; // ms
34 int infoMessageInterval = 200; // ms
35 double maneuver_plan_dt = 15; // s
36 // following parameters are for IHP gap regulation algorithm
37 double time_step = 15; // s
38 double epislon = 0.001; // m/s
39
40 // following parameters are for platoon forming and operation
41 double timeHeadway = 2.0; // s
42 double standStillHeadway = 12.0; // m
43 double maxAllowedJoinTimeGap = 15.0; // s
44 double maxAllowedJoinGap = 90.0; // m
45 double minAllowedJoinGap = 5.0; // m
46 double longitudinalCheckThresold = 85.0; // m
47 double desiredJoinTimeGap = 4.0; // s
48 double desiredJoinGap = 30.0; // m
49 int maxLeaderAbortingCalls = 2; // counter
50 double waitingStateTimeout = 25.0; // s
51 double cmdSpeedMaxAdjustment = 10.0; // m/s
52
53 // following parameters are mainly for APF leader selection
54 // UCLA: Rename the next four variables for better explainability.
55 double minAllowableHeadaway = 1.6; // s
56 double headawayStableLowerBond = 1.7; // s
57 double maxAllowableHeadaway = 4.0; // s
58 double headawayStableUpperBond = 3.9; // s
59
60 double minCutinGap = 22.0; // m
61 double maxCutinGap = 22.0; // m
62 double maxCrosstrackError = 2.0; // m
63
64 // Speed adjuster to slow down platoon memebr to create gap
65 double slowDownAdjuster = 0.75; // ratio
66 double createGapAdjuster = 0.3; // ratio
67
68 std::string vehicleID = "default_id";
69
70 // min speed to start platooning negotiations
71 double minPlatooningSpeed = 7.0; // m/s
72
73 // ---------------------- UCLA: parameters for IHP platoon trajectory regulation ----------------
78 double ss_theta = 4.0; // Stanstill determining threshold, in m/s.
79 double standstill = 2.0; // Stanstill reaction time adjuster, in s.
80 double inter_tau = 1.5; // Inter-platoon time gap, refer to bumper to bumper gap time, in s.
81 double intra_tau = 0.6; // Intra-platoon time gao, refer to bumper to bumper gap time, in s.
82 double gap_weight = 0.9; // Weighted ratio for time-gap based calculation, unitless.
83 bool test_front_join = false; //Flag to enable/disable front join functionality with two vehicles.
84 // Flag can be set to true, to test front join functionality with two vehicles
85 // But in normal operating conditions it should be set to false
86 bool test_cutin_join = false; //Flag to enable/disable front/rear cutin join functionality with only 2 vehicles
87 //Normal operations it should be false, but true allows a cutin to a single-car platoon
88 //------------------------------------------------------------------------------------------------
89 bool allowCutinJoin = true; //Flag to enable/disable cut-in joins
90 double significantDTDchange = 0.2; // Ratio of dtd that is considered a significant change and triggers a new sort of platoon vector
91 int join_index = -1; // target join index for cut-in join - used for testing purposes. -1: front cutin join, target_platoon.size()-1: cut-in rear
92
93
94 friend std::ostream& operator<<(std::ostream& output, const PlatoonPluginConfig& c)
95 {
96 output << "PlatoonPluginConfig { " << std::endl
97 << "maxPlatoonSize: " << c.maxPlatoonSize << std::endl
98 << "algorithmType: " << c.algorithmType << std::endl
99 << "statusMessageInterval: " << c.statusMessageInterval << std::endl
100 << "infoMessageInterval: " << c.infoMessageInterval << std::endl
101 << "timeHeadway: " << c.timeHeadway << std::endl
102 << "standStillHeadway: " << c.standStillHeadway << std::endl
103 << "maxAllowedJoinTimeGap: " << c.maxAllowedJoinTimeGap << std::endl
104 << "desiredJoinTimeGap: " << c.desiredJoinTimeGap << std::endl
105 << "desiredJoinGap: " << c.desiredJoinGap << std::endl
106 << "maxLeaderAbortingCalls: " << c.maxLeaderAbortingCalls << std::endl
107 << "waitingStateTimeout: " << c.waitingStateTimeout << std::endl
108 << "cmdSpeedMaxAdjustment: " << c.cmdSpeedMaxAdjustment << std::endl
109 << "minAllowableHeadaway: " << c.minAllowableHeadaway << std::endl
110 << "maxAllowableHeadaway: " << c.maxAllowableHeadaway << std::endl
111 << "headawayStableLowerBond: " << c.headawayStableLowerBond << std::endl
112 << "headawayStableUpperBond: " << c.headawayStableUpperBond << std::endl
113 << "minCutinGap: " << c.minCutinGap << std::endl
114 << "maxCutinGap: " << c.maxCutinGap << std::endl
115 << "maxCrosstrackError: " << c.maxCrosstrackError << std::endl
116 << "vehicleID: " << c.vehicleID << std::endl
117 << "minPlatooningSpeed: " << c.minPlatooningSpeed << std::endl
118 << "allowCutinJoin: " << c.allowCutinJoin << std::endl
119 << "significantDTDchange: " << c.significantDTDchange << std::endl
120 << "join_index: " << c.join_index << std::endl
121 << "}" << std::endl; //TODO this is missing some fields
122 return output;
123 }
124};
125
126} //platoon_strategic_ihp
Stuct containing the algorithm configuration values for the yield_pluginConfig.
double ss_theta
Parameter sets for IHP platoon trajectory regulation algorithm. Please refer to the updated design do...
friend std::ostream & operator<<(std::ostream &output, const PlatoonPluginConfig &c)