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_manager_ihp.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2019-2021 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/*
18 * Developed by the UCLA Mobility Lab, 10/20/2021.
19 *
20 * Creator: Xu Han
21 * Author: Xu Han, Xin Xia, Jiaqi Ma
22 */
23
26#include <boost/algorithm/string.hpp>
27#include <rclcpp/logging.hpp>
28#include <array>
29
31{
51 PlatoonManager::PlatoonManager(std::shared_ptr<carma_ros2_utils::timers::TimerFactory> timer_factory) : timer_factory_(std::move(timer_factory))
52 {
53 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Top of PlatoonManager ctor.");
54 }
55
56
57 // Update the location of the host in the vector of platoon members
58 void PlatoonManager::updateHostPose(const double downtrack, const double crosstrack)
59 {
60 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Host (index " << hostPosInPlatoon_ << "): downtrack = " << downtrack << ", crosstrack = " << crosstrack);
61 host_platoon_[hostPosInPlatoon_].vehiclePosition = downtrack;
62 host_platoon_[hostPosInPlatoon_].vehicleCrossTrack = crosstrack;
63 }
64
65 // Update the speed info of the host in the vector of platoon members
66 void PlatoonManager::updateHostSpeeds(const double cmdSpeed, const double actualSpeed)
67 {
68 host_platoon_[hostPosInPlatoon_].commandSpeed = cmdSpeed;
69 host_platoon_[hostPosInPlatoon_].vehicleSpeed = actualSpeed;
70 }
71
72 // Update/add one member's information from STATUS messages, update platoon ID if needed.
73 void PlatoonManager::hostMemberUpdates(const std::string& senderId, const std::string& platoonId, const std::string& params,
74 const double& DtD, const double& CtD)
75 {
76
77 // parse params, read member data
78 std::vector<std::string> inputsParams;
79 boost::algorithm::split(inputsParams, params, boost::is_any_of(","));
80 // read command speed, m/s
81 std::vector<std::string> cmd_parsed;
82 boost::algorithm::split(cmd_parsed, inputsParams[0], boost::is_any_of(":"));
83 double cmdSpeed = std::stod(cmd_parsed[1]);
84 // get DtD directly instead of parsing message, m
85 double dtDistance = DtD;
86 // get CtD directly
87 double ctDistance = CtD;
88 // read current speed, m/s
89 std::vector<std::string> cur_parsed;
90 boost::algorithm::split(cur_parsed, inputsParams[1], boost::is_any_of(":"));
91 double curSpeed = std::stod(cur_parsed[1]);
92
93 // If we are currently in a follower state:
94 // 1. We will update platoon ID based on leader's STATUS
95 // 2. We will update platoon members info based on platoon ID for all members
96 if (isFollower)
97 {
98 // Sanity check
99 if (platoonLeaderID.compare(host_platoon_[0].staticId) != 0)
100 {
101 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "///// platoonLeaderID NOT PROPERLY ASSIGNED! Value = " << platoonLeaderID
102 << ", host_platoon_[0].staticId = " << host_platoon_[0].staticId);
103 }
104
105 // read message status
106 bool isFromLeader = platoonLeaderID == senderId;
107 bool needPlatoonIdChange = isFromLeader && (currentPlatoonID != platoonId);
108
109 if(needPlatoonIdChange)
110 {
111 // TODO: better to have leader explicitly inform us that it is merging into another platoon, rather than require us to deduce it here.
112 // This condition may also result from missing some message traffic, new leader in this platoon, or other confusion/incorrect code.
113 // Consider using a new STATUS msg param that tells members of new platoon ID and new leader ID when a change is made.
114 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "It seems that the current leader is joining another platoon.");
115 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "So the platoon ID is changed from " << currentPlatoonID << " to " << platoonId);
116 currentPlatoonID = platoonId;
117 updatesOrAddMemberInfo(host_platoon_, senderId, cmdSpeed, dtDistance, ctDistance, curSpeed);
118 }
119 else if (currentPlatoonID == platoonId)
120 {
121 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "This STATUS messages is from our platoon. Updating the info...");
122 updatesOrAddMemberInfo(host_platoon_, senderId, cmdSpeed, dtDistance, ctDistance, curSpeed);
123 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "The first vehicle in our list is now " << host_platoon_[0].staticId);
124 }
125 else //sender is in a different platoon
126 {
127 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "This STATUS message is not from a vehicle we care about. Ignore this message with id: " << senderId);
128 }
129 }
130 else //host is leader
131 {
132 // If we are currently in any leader state, we only update platoon member based on platoon ID
133 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Host is leader: currentPlatoonID = " << currentPlatoonID << ", incoming platoonId = " << platoonId);
134 if (currentPlatoonID == platoonId)
135 {
136 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "This STATUS messages is from our platoon. Updating the info...");
137 updatesOrAddMemberInfo(host_platoon_, senderId, cmdSpeed, dtDistance, ctDistance, curSpeed);
138 }
139 else
140 {
141 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Platoon IDs not matched");
142 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "currentPlatoonID: " << currentPlatoonID);
143 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "incoming platoonId: " << platoonId);
144 }
145 }
146
147 // update host vehicle information each time new member is updated. Now platoon contains host vehicle.
148 std::string hostStaticId = getHostStaticID();
149 double hostcmdSpeed = getCommandSpeed();
150 double hostDtD = getCurrentDowntrackDistance();
151 double hostCtD = getCurrentCrosstrackDistance();
152 double hostCurSpeed = getCurrentSpeed();
153 updatesOrAddMemberInfo(host_platoon_, hostStaticId, hostcmdSpeed, hostDtD, hostCtD, hostCurSpeed);
154 }
155
156 // Update/add one member's information from STATUS messages, update platoon ID if needed.
157 void PlatoonManager::neighborMemberUpdates(const std::string& senderId, const std::string& platoonId, const std::string& params,
158 const double& DtD, const double& CtD)
159 {
160
161 // parse params, read member data
162 std::vector<std::string> inputsParams;
163 boost::algorithm::split(inputsParams, params, boost::is_any_of(","));
164 // read command speed, m/s
165 std::vector<std::string> cmd_parsed;
166 boost::algorithm::split(cmd_parsed, inputsParams[0], boost::is_any_of(":"));
167 double cmdSpeed = std::stod(cmd_parsed[1]);
168 // get DtD directly instead of parsing message, m
169 double dtDistance = DtD;
170 // get CtD directly
171 double ctDistance = CtD;
172 // read current speed, m/s
173 std::vector<std::string> cur_parsed;
174 boost::algorithm::split(cur_parsed, inputsParams[1], boost::is_any_of(":"));
175 double curSpeed = std::stod(cur_parsed[1]);
176
177 if (neighborPlatoonID == platoonId)
178 {
179 updatesOrAddMemberInfo(neighbor_platoon_, senderId, cmdSpeed, dtDistance, ctDistance, curSpeed);
180 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "This STATUS messages is from the target platoon. Updating the info...");
181 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "The first vehicle in that platoon is now " << neighbor_platoon_[0].staticId);
182
183 // If we have data on all members of a neighboring platoon, set a complete record flag
186 {
188 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Neighbor record is complete!");
189 }
190 }
191 else //sender is in a different platoon
192 {
193 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "This STATUS message is not from a vehicle we care about. Ignore this message from sender: "
194 << senderId << " about platoon: " << platoonId);
195 }
196 }
197
198 // Check a new vehicle's existence; add its info to the platoon if not in list, update info if already existed.
199 void PlatoonManager::updatesOrAddMemberInfo(std::vector<PlatoonMember>& platoon, std::string senderId, double cmdSpeed,
200 double dtDistance, double ctDistance, double curSpeed)
201 {
202 bool isExisted = false;
203 bool sortNeeded = false;
204
205 // update/add this info into the list
206 for (size_t i = 0; i < platoon.size(); ++i){
207 if(platoon[i].staticId == senderId) {
208 if (abs(dtDistance - platoon[i].vehiclePosition)/(platoon[i].vehiclePosition + 0.01) > config_.significantDTDchange)
209 {
210 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "DTD of member " << platoon[i].staticId << " is changed significantly, so a new sort is needed");
211
212 sortNeeded = true;
213 }
214 platoon[i].commandSpeed = cmdSpeed; // m/s
215 platoon[i].vehiclePosition = dtDistance; // m
216 platoon[i].vehicleCrossTrack = ctDistance; // m
217 platoon[i].vehicleSpeed = curSpeed; // m/s
218 platoon[i].timestamp = timer_factory_->now().nanoseconds()/1000000;
219 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Receive and update platooning info on member " << i << ", ID:" << platoon[i].staticId);
220 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " CommandSpeed = " << platoon[i].commandSpeed);
221 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " Actual Speed = " << platoon[i].vehicleSpeed);
222 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " Downtrack Location = " << platoon[i].vehiclePosition);
223 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " Crosstrack dist = " << platoon[i].vehicleCrossTrack);
224
225 if (senderId == HostMobilityId)
226 {
228 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " This is the HOST vehicle");
229 }
230 isExisted = true;
231 }
232 }
233
234 if (sortNeeded)
235 {
236 // sort the platoon member based on dowtrack distance (m) in an descending order.
237 std::sort(std::begin(platoon), std::end(platoon), [](const PlatoonMember &a, const PlatoonMember &b){return a.vehiclePosition > b.vehiclePosition;});
238 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Platoon is re-sorted due to large difference in dtd update.");
239 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " Platoon order is now:");
240 for (size_t i = 0; i < platoon.size(); ++i)
241 {
242 std::string hostFlag = " ";
243 if (platoon[i].staticId == getHostStaticID())
244 {
246 hostFlag = "Host";
247 }
248 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " " << platoon[i].staticId << "its DTD: " << platoon[i].vehiclePosition << " " << hostFlag);
249 }
250 }
251
252 // if not already exist, add to platoon list.
253 if(!isExisted) {
254 long cur_t = timer_factory_->now().nanoseconds()/1000000; // time in millisecond
255
256 PlatoonMember newMember = PlatoonMember(senderId, cmdSpeed, curSpeed, dtDistance, ctDistance, cur_t);
257 platoon.push_back(newMember);
258 // sort the platoon member based on downtrack distance (m) in an descending order.
259 std::sort(std::begin(platoon), std::end(platoon), [](const PlatoonMember &a, const PlatoonMember &b){return a.vehiclePosition > b.vehiclePosition;});
260
261 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Add a new vehicle into our platoon list " << newMember.staticId << " platoon.size now = " << platoon.size());
262 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " Platoon order is now:");
263 for (size_t i = 0; i < platoon.size(); ++i)
264 {
265 std::string hostFlag = " ";
266 if (platoon[i].staticId == getHostStaticID())
267 {
269 hostFlag = "Host";
270 }
271 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), " " << platoon[i].staticId << "its DTD: " << platoon[i].vehiclePosition << " " << hostFlag);
272 }
273 }
274 }
275
276 // TODO: Place holder for delete member info due to dissolve operation.
277
278 // Get the platoon size.
280 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "host platoon size: " << host_platoon_.size());
281 return host_platoon_.size();
282 }
283
284 // Reset variables to indicate there is no current action in work
286 {
287 current_plan.valid = false;
291 // Leave the platoon & leader IDs alone since we might continue to be in one
292 }
293
294 // Reset variables to indicate there is no platoon - host is a solo vehicle again
296 {
297 // Remove any elements in the platoon vector other than the host vehicle
298 if (host_platoon_.size() > hostPosInPlatoon_ + 1)
299 {
301 }
303
304 // Clean up other variables
308 isCreateGap = false;
310 }
311
312 // Reset variables to indicate there is no known neighbor platoon
314 {
315 neighbor_platoon_.clear();
320 }
321
322 bool PlatoonManager::removeMember(const size_t mem)
323 {
324 // Don't remove ourselves!
325 if (hostPosInPlatoon_ == mem)
326 {
327 return false;
328 }
329
330 // Don't remove a member that isn't there
331 else if (host_platoon_.size() <= 1 || mem >= host_platoon_.size())
332 {
333 return false;
334 }
335
336 if (mem < hostPosInPlatoon_)
337 {
339 }
340 host_platoon_.erase(host_platoon_.begin() + mem, host_platoon_.begin() + mem + 1);
341
342 // If host is the only remaining member then clean up the other platoon data
343 if (host_platoon_.size() == 1)
344 {
348 }
349
350 return true;
351 }
352
353 bool PlatoonManager::removeMemberById(const std::string id)
354 {
355 // Don't remove ourselves!
356 if (id.compare(HostMobilityId) == 0)
357 {
358 return false;
359 }
360
361 // Search for the member with a matching ID and remove it
362 for (size_t m = 0; m < host_platoon_.size(); ++m)
363 {
364 if (id.compare(host_platoon_[m].staticId) == 0)
365 {
366 return removeMember(m);
367 }
368 }
369
370 // Indicate the member was not found
371 return false;
372 }
373
374 // Find the downtrack distance of the last vehicle of the platoon, in m.
376 // due to downtrack descending order, the 1ast vehicle in list is the platoon rear vehicle.
377 // Even if host is solo, platoon size is 1 so this works.
378 return host_platoon_[host_platoon_.size()-1].vehiclePosition;
379 }
380
381 // Find the downtrack distance of the first vehicle of the platoon, in m.
383 // due to downtrack descending order, the firest vehicle in list is the platoon front vehicle.
384 return host_platoon_[0].vehiclePosition;
385 }
386
387 // Return the dynamic leader (i.e., the vehicle to follow) of the host vehicle.
389 PlatoonMember dynamicLeader;
390 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "host_platoon_ size: " << host_platoon_.size());
391 if(isFollower)
392 {
393 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Leader initially set as first vehicle in platoon");
394 // return the first vehicle in the platoon as default if no valid algorithm applied
395 // due to downtrack descending order, the platoon front veihcle is the first in list.
396 dynamicLeader = host_platoon_[0];
397 if (algorithmType_ == "APF_ALGORITHM"){
398 size_t newLeaderIndex = allPredecessorFollowing();
399
400 dynamic_leader_index_ = (int)newLeaderIndex;
401 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "dynamic_leader_index_: " << dynamic_leader_index_);
402 if(newLeaderIndex < host_platoon_.size()) { //this must always be true!
403 dynamicLeader = host_platoon_[newLeaderIndex];
404 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF output: " << dynamicLeader.staticId);
407 }
408 else //something is terribly wrong in the logic!
409 {
410 RCLCPP_WARN_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "newLeaderIndex = " << newLeaderIndex << " is invalid coming from allPredecessorFollowing!");
415 dynamicLeader = host_platoon_[getNumberOfVehicleInFront() - 1];
416 // update index and ID
419 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "Based on the output of APF algorithm we start to follow our predecessor.");
420 }
421 }
422 }
423 return dynamicLeader;
424
425 }
426
427 // The implementation of all predecessor following algorithm. Determine the dynamic leader for the host vehicle to follow.
429
431 // If the host vehicle is the second follower of a platoon, it will always follow the platoon leader in the front
433 {
434 // If the host is the second vehicle, then follow the leader.
435 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "As the second vehicle in the platoon, it will always follow the leader. Case Zero");
436 return 0;
437 }
439 // If there weren't a leader in the previous time step, follow the first vehicle (i.e., the platoon leader) as default.
441 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF algorithm did not found a dynamic leader in previous time step. Case one");
442 return 0;
443 }
444
445 //***** Formulate speed and downtrack vector *****//
446 // Update host vehicle info when update member info, so platoon list include host vehicle, direct use platoon size for downtrack/speed vector.
447 // Record downtrack distance (m) of each member
448 std::vector<double> downtrackDistance(hostPosInPlatoon_);
449 for(size_t i = 0; i < hostPosInPlatoon_; i++) {
450 downtrackDistance[i] = host_platoon_[i].vehiclePosition; // m
451 }
452 // Record speed (m/s) of each member
453 std::vector<double> speed(host_platoon_.size());
454 for(size_t i = 0; i < host_platoon_.size(); i++) {
455 speed[i] = host_platoon_[i].vehicleSpeed; // m/s
456 }
457
458
460 // If the distance headway between the subject vehicle and its predecessor is an issue
461 // according to the "min_gap" and "max_gap" thresholds, then it should follow its predecessor
462 // The following line will not throw exception because the length of downtrack array is larger than two in this case
463 double distHeadwayWithPredecessor = downtrackDistance[hostPosInPlatoon_ - 1] - downtrackDistance[hostPosInPlatoon_];
464 gapWithPred_ = distHeadwayWithPredecessor;
465 if(insufficientGapWithPredecessor(distHeadwayWithPredecessor)) {
466 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF algorithm decides there is an issue with the gap with preceding vehicle: " << distHeadwayWithPredecessor << " m. Case Two");
467 return hostPosInPlatoon_ - 1;
468 }
469 else{
470 // implementation of the main part of APF algorithm
471 // calculate the time headway between every consecutive pair of vehicles
472 std::vector<double> timeHeadways = calculateTimeHeadway(downtrackDistance, speed);
473 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF calculate time headways: " );
474 for (const auto& value : timeHeadways)
475 {
476 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF time headways: " << value);
477 }
478 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found the previous dynamic leader is " << previousFunctionalDynamicLeaderID_);
479 // if the previous dynamic leader is the first vehicle in the platoon
480
482
484 // If there is a violation, the return value is the desired dynamic leader index
485 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF use violations on lower boundary or maximum spacing to choose dynamic leader. Case Three.");
486 return determineDynamicLeaderBasedOnViolation(timeHeadways);
487 }
488 else{
489 // if the previous dynamic leader is not the first vehicle
490 // get the time headway between every consecutive pair of vehicles from index Of Previous dynamic Leader
491 std::vector<double> partialTimeHeadways = getTimeHeadwayFromIndex(timeHeadways, previousFunctionalDynamicLeaderIndex_);
492 for (const auto& value : partialTimeHeadways)
493 {
494 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF partial time headways: " << value);
495 }
496 int closestLowerBoundaryViolation = findLowerBoundaryViolationClosestToTheHostVehicle(partialTimeHeadways);
497 int closestMaximumSpacingViolation = findMaximumSpacingViolationClosestToTheHostVehicle(partialTimeHeadways);
498 // if there are no violations anywhere between the subject vehicle and the current dynamic leader,
499 // then depending on the time headways of the ENTIRE platoon, the subject vehicle may switch
500 // dynamic leader further downstream. This is because the subject vehicle has determined that there are
501 // no time headways between itself and the current dynamic leader which would cause the platoon to be unsafe.
502 // if there are violations somewhere betweent the subject vehicle and the current dynamic leader,
503 // then rather than assigning dynamic leadership further DOWNSTREAM, we must go further UPSTREAM in the following lines
504 if(closestLowerBoundaryViolation == -1 && closestMaximumSpacingViolation == -1) {
505 // In order for the subject vehicle to assign dynamic leadership further downstream,
506 // two criteria must be satisfied: first the leading vehicle and its immediate follower must
507 // have a time headway greater than "upper_boundary." The purpose of this criteria is to
508 // introduce a hysteresis in order to eliminate the possibility of a vehicle continually switching back
509 // and forth between two dynamic leaders because one of the time headways is hovering right around
510 // the "lower_boundary" threshold; second the leading vehicle and its predecessor must have
511 // a time headway less than "min_spacing" second. Just as with "upper_boundary", "min_spacing" exists to
512 // introduce a hysteresis where dynamic leaders are continually being switched.
514 bool condition2 = timeHeadways[previousFunctionalDynamicLeaderIndex_ - 1] < config_.headawayStableUpperBond;
515
517 //we may switch dynamic leader further downstream
518 if(condition1 && condition2) {
519 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found two conditions for assigning local dynamic leadership further downstream are satisfied. Case Four");
520 return determineDynamicLeaderBasedOnViolation(timeHeadways);
521 } else {
522
524 // We may not switch dynamic leadership to another vehicle further downstream because some criteria are not satisfied
525 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found two conditions for assigning local dynamic leadership further downstream are not satisfied. Case Five.");
526 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "condition1: " << condition1 << " & condition2: " << condition2);
528 }
529 } else if(closestLowerBoundaryViolation != -1 && closestMaximumSpacingViolation == -1) {
530 // The rest four cases have roughly the same logic: locate the closest violation and assign dynamic leadership accordingly
531
533 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found closestLowerBoundaryViolation on partial time headways. Case Six.");
534 return previousFunctionalDynamicLeaderIndex_ - 1 + closestLowerBoundaryViolation;
535
536 } else if(closestLowerBoundaryViolation == -1 && closestMaximumSpacingViolation != -1) {
537
539 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found closestMaximumSpacingViolation on partial time headways. Case Seven.");
540 return previousFunctionalDynamicLeaderIndex_ + closestMaximumSpacingViolation;
541 } else{
542 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found closestMaximumSpacingViolation and closestLowerBoundaryViolation on partial time headways.");
543 if(closestLowerBoundaryViolation > closestMaximumSpacingViolation) {
544
546 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "closest LowerBoundaryViolation is higher than closestMaximumSpacingViolation on partial time headways. Case Eight.");
547 return previousFunctionalDynamicLeaderIndex_ - 1 + closestLowerBoundaryViolation;
548 } else if(closestLowerBoundaryViolation < closestMaximumSpacingViolation) {
549
551 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "closestMaximumSpacingViolation is higher than closestLowerBoundaryViolation on partial time headways. Case Nine.");
552 return previousFunctionalDynamicLeaderIndex_ + closestMaximumSpacingViolation;
553 } else {
554 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF dynamic Leader selection parameter is wrong!");
555 return 0;
556 }
557 }
558 }
559
560 }
561 }
562
563 // Find the time headaway (s) sub-list based on the platoon wise comprehensive time headaway list, starting index is indicated by the parameter: "start".
564 std::vector<double> PlatoonManager::getTimeHeadwayFromIndex(std::vector<double> timeHeadways, int start) const {
565 std::vector<double> result(timeHeadways.begin() + start-1, timeHeadways.end());
566 return result;
567 }
568
569 // Determine if the gap (m) between host and predecessor is big enough, with regards to minGap_ (m) and maxGap_ (m).
570 bool PlatoonManager::insufficientGapWithPredecessor(double distanceToPredVehicle) {
571
572 // For normal operation, gap > minGap is necessary.
573 bool frontGapIsTooSmall = distanceToPredVehicle < config_.minCutinGap;
574
575 // Host vehicle was following predecessor vehicle. --> The predecessor vehicle was violating gap threshold.
576 bool previousLeaderIsPredecessor = previousFunctionalDynamicLeaderID_ == host_platoon_[host_platoon_.size() - 1].staticId;
577
578 // Gap greater than maxGap_ is necessary for host to stop choosing predecessor as dynamic leader.
579 bool frontGapIsNotLargeEnough = distanceToPredVehicle < config_.maxCutinGap && previousLeaderIsPredecessor;
580
581 return (frontGapIsTooSmall || frontGapIsNotLargeEnough);
582 }
583
584 // Calculate the time headway (s) behind each vehicle of the platoon. If no one behind or following car stoped, return infinity.
585 std::vector<double> PlatoonManager::calculateTimeHeadway(std::vector<double> downtrackDistance, std::vector<double> speed) const{
586 std::vector<double> timeHeadways(downtrackDistance.size() - 1);
587 // Due to downtrack descending order, the platoon member with smaller index has larger downtrack, hence closer to the front of the platoon.
588 for (size_t i = 0; i < timeHeadways.size(); i++){
589 // Calculate time headaway between the vehicle behind.
590 if (speed[i+1] >= config_.ss_theta) // speed is in m/s
591 {
592 timeHeadways[i] = (downtrackDistance[i] - downtrackDistance[i+1]) / speed[i+1]; // downtrack is in m, speed is in m/s.
593 }
594 // If no one behind or following car stoped, return infinity.
595 else
596 {
597 timeHeadways[i] = std::numeric_limits<double>::infinity();
598 }
599 }
600 return timeHeadways; // time is in s.
601 }
602
603 // Determine the dynamic leader ID based on gap threshold violation's index.
604 int PlatoonManager::determineDynamicLeaderBasedOnViolation(std::vector<double> timeHeadways){
605
619 // Find the closest violations.
620 int closestLowerBoundaryViolation = findLowerBoundaryViolationClosestToTheHostVehicle(timeHeadways);
621 int closestMaximumSpacingViolation = findMaximumSpacingViolationClosestToTheHostVehicle(timeHeadways);
622
623 // Compare the violation locations, always following the closer violation vehicle (larger index) first, then the furthur ones.
624 if(closestLowerBoundaryViolation > closestMaximumSpacingViolation) {
625 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found violation on closestLowerBoundaryViolation at " << closestLowerBoundaryViolation);
626 return closestLowerBoundaryViolation; // Min violation, following the vehicle that is in font of the violating gap.
627 }
628 else if(closestLowerBoundaryViolation < closestMaximumSpacingViolation){
629 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found violation on closestMaximumSpacingViolation at " << closestMaximumSpacingViolation);
630 return closestMaximumSpacingViolation + 1; // Max violation, follow the vehicle that is behinf the violating gap.
631 }
632 else{
633 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "APF found no violations on both closestLowerBoundaryViolation and closestMaximumSpacingViolation");
634 return 0;
635 }
636 }
637
638 // Find the lower boundary violation vehicle that closest to the host vehicle. If no violation found, return -1.
639 int PlatoonManager::findLowerBoundaryViolationClosestToTheHostVehicle(std::vector<double> timeHeadways) const{
640 // Due to descending downtrack order, the search starts from the platoon rear, which corresponds to last in list.
641 for(int i = timeHeadways.size()-1; i >= 0; i--) {
642 if(timeHeadways[i] < config_.minAllowableHeadaway) // in s
643 {
644 return i;
645 }
646 }
647 return -1;
648 }
649
650 // Find the maximum spacing violation vehicle that closest to the host vehicle. If no violation found, return -1.
651 int PlatoonManager::findMaximumSpacingViolationClosestToTheHostVehicle(std::vector<double> timeHeadways) const {
652 // UCLA: Add maxAllowableHeadaway adjuster to increase the threshold during gap creating period.
653 double maxAllowableHeadaway_adjusted = config_.maxAllowableHeadaway;
654 if (isCreateGap) {
655 // adjust maximum allowed headway to allow for a bigger gap
656 maxAllowableHeadaway_adjusted = maxAllowableHeadaway_adjusted*(1 + config_.createGapAdjuster);
657 }
658
659 // Due to descending downtrack order, the search starts from the platoon rear, which corresponds to last in list.
660 for(int i = timeHeadways.size()-1; i >= 0 ; i--) {
661 if(timeHeadways[i] > maxAllowableHeadaway_adjusted) // in s
662 {
663 return i;
664 }
665 }
666 return -1;
667 }
668
669 // Change the local platoon manager from follower operation state to leader operation state for single vehicle status change.
670 // This could happen because host is 2nd in line and leader is departing, or because APF algorithm decided host's gap is too
671 // large and we need to separate from front part of platoon.
673
674 // Get current host info - assumes departing leader or front of platoon hasn't already been removed from the vector
676
677 // Clear the front part of the platoon info, since we are splitting off from it; leaves host as element 0
678 if (hostPosInPlatoon_ > 0)
679 {
681 }else
682 {
683 RCLCPP_WARN(rclcpp::get_logger("platoon_strategic_ihp"), "### Host becoming leader, but is already at index 0 in host_platoon_ vector! Vector unchanged.");
684 }
685
687 isFollower = false;
688 currentPlatoonID = boost::uuids::to_string(boost::uuids::random_generator()());
691 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "The platoon manager is changed from follower state to leader state. New platoon ID = " << currentPlatoonID);
692 }
693
694 // Change the local platoon manager from leader operation state to follower operation state for single vehicle status change.
695 // This could happen because another vehicle did a front join and host is now 2nd in line, or because host was a solo vehicle
696 // that just completed joining a platoon at any position.
697 // Note: The platoon list will be firstly reset to only include the new leader and the host, then allowed to gradually repopulate via
698 // updateMembers() as new MobilityOperation messages come in.
699 void PlatoonManager::changeFromLeaderToFollower(std::string newPlatoonId, std::string newLeaderId) {
700
701 // Save the current host info
703
704 // Clear contents of the platoon vector and rebuild it with the two known members at this time, leader & host.
705 // Remaining leader info and info about any other members will get populated as messages come in.
706 PlatoonMember newLeader = PlatoonMember();
707 newLeader.staticId = newLeaderId;
708 host_platoon_.clear();
709 host_platoon_.push_back(newLeader); //can get location info updated later with a STATUS or INFO message
710 host_platoon_.push_back(hostInfo);
711
712 hostPosInPlatoon_ = 1; //since host was previously leader it is now guaranteed to be 2nd in the line (index 1)
713 isFollower = true;
714 currentPlatoonID = newPlatoonId;
715
716 // Clear the record of neighbor platoon, since we likely just joined it
718
719 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "The platoon manager is changed from leader state to follower state. Platoon vector re-initialized. Plan ID = " << newPlatoonId);
720 }
721
722 // Return the number of vehicles in the front of the host vehicle. If host is leader or a single vehicle, return 0.
724 return hostPosInPlatoon_;
725 }
726
727 // Return the distance (m) to the predecessor vehicle.
729 return gapWithPred_;
730 }
731
732 // Return the current host vehicle speed in m/s.
734 return host_platoon_[hostPosInPlatoon_].vehicleSpeed;
735 }
736
737 // Return the current command speed of host vehicle in m/s.
739 {
740 return host_platoon_[hostPosInPlatoon_].commandSpeed;
741 }
742
743 // Return the current downtrack distance in m.
745 {
746 return host_platoon_[hostPosInPlatoon_].vehiclePosition;
747 }
748
749 // Return the current crosstrack distance, in m.
751 {
752 return host_platoon_[hostPosInPlatoon_].vehicleCrossTrack;
753 }
754
755 // UCLA: return the host vehicle static ID.
757 {
758 return HostMobilityId;
759 }
760
761 // Return the physical length from platoon front vehicle (front bumper) to platoon rear vehicle (rear bumper) in m.
763 //this works even if platoon size is 1 (can't be 0)
764 return host_platoon_[0].vehiclePosition - host_platoon_[host_platoon_.size() - 1].vehiclePosition + config_.vehicleLength;
765 }
766
767 // ---------------------- UCLA: IHP platoon trajectory regulation --------------------------- //
768 // Calculate the time headway summation of the vehicle in front of the host
770 {
771 // 1. read dtd vector
772 // dtd vector
773 std::vector<double> downtrackDistance(host_platoon_.size());
774 for (size_t i = 0; i < host_platoon_.size(); i++)
775 {
776 downtrackDistance[i] = host_platoon_[i].vehiclePosition;
777 }
778 // speed vector
779 std::vector<double> speed(host_platoon_.size());
780 for (size_t i = 0; i < host_platoon_.size(); i++)
781 {
782 speed[i] = host_platoon_[i].vehicleSpeed;
783 }
784
785 // 2. find the summation of "veh_len/veh_speed" for all predecessors
786 double tmp_time_hdw = 0.0;
787 double cur_dtd;
788 for (size_t index = 0; index < downtrackDistance.size(); index++)
789 {
790 cur_dtd = downtrackDistance[index];
791 if (cur_dtd > getCurrentDowntrackDistance())
792 {
793 // greater dtd ==> in front of host veh
794 tmp_time_hdw += config_.vehicleLength / (speed[index] + 0.00001);
795 }
796 }
797
798 // Return the calcualted value
799 return tmp_time_hdw;
800 }
801
802 // Return the predecessor speed
804 {
805 return host_platoon_[hostPosInPlatoon_].vehicleSpeed; // m/s
806 }
807
808 // Return the predecessor location
810 {
811 // Read host index.
812 int host_platoon_index = getNumberOfVehicleInFront();
813
814 // Return speed
815 return host_platoon_[host_platoon_index].vehiclePosition; // m
816 }
817
818 // Trajectory based platoon trajectory regulation.
820 {
829 // 1. read dtd vector
830 // dtd vector
831 std::vector<double> downtrackDistance(host_platoon_.size());
832 for (size_t i = 0; i < host_platoon_.size(); i++)
833 {
834 downtrackDistance[i] = host_platoon_[i].vehiclePosition;
835 }
836 // speed vector
837 std::vector<double> speed(host_platoon_.size());
838 for (size_t i = 0; i < host_platoon_.size(); i++)
839 {
840 speed[i] = host_platoon_[i].vehicleSpeed;
841 }
842
843 // 2. find the summation of "veh_len/veh_speed" for all predecessors
844 double tmp_time_hdw = 0.0;
845 double cur_dtd;
846 for (size_t index = 0; index < downtrackDistance.size(); index++)
847 {
848 cur_dtd = downtrackDistance[index];
849 if (cur_dtd > getCurrentDowntrackDistance())
850 {
851 // greater dtd ==> in front of host veh
852 tmp_time_hdw += config_.vehicleLength / (speed[index] + 0.00001);
853 }
854 }
855
856 // 3. read host veh and front veh info
857 // Predecessor vehicle data.
858 double pred_spd = speed[getNumberOfVehicleInFront()-1]; // m/s
859 double pred_pos = downtrackDistance[getNumberOfVehicleInFront()-1]; // m
860
861 // host data.
862 double ego_spd = getCurrentSpeed(); // m/s
863 double ego_pos = getCurrentDowntrackDistance(); // m
864
865 // platoon position index
866 int pos_idx = getNumberOfVehicleInFront();
867
868 double desirePlatoonGap = config_.intra_tau; //s
869
870 // IHP desired position calculation methods
871 double pos_g; // desired downtrack position calculated with time-gap, in m.
872 double pos_h; // desired downtrack position calculated with distance headaway, in m.
873
874 // 4. IHP gap regualtion
875
876 // intermediate variables
877 double timeGapAndStepRatio = desirePlatoonGap/time_step; // The ratio between desired platoon time gap and the current time_step.
878 double totalTimeGap = desirePlatoonGap*pos_idx; // The overall time gap from host vehicle to the platoon leader, in s.
879
880 // calcilate pos_gap and pos_headway
881 if ((pred_spd <= ego_spd) && (ego_spd <= config_.ss_theta))
882 {
883 // ---> 4.1 pos_g
884 pos_g = (pred_pos - config_.vehicleLength - config_.standstill + ego_pos*timeGapAndStepRatio) / (1 + timeGapAndStepRatio);
885 // ---> 4.2 pos_h
886 double pos_h_nom = (pred_pos - config_.standstill + ego_pos*(totalTimeGap + tmp_time_hdw)/time_step);
887 double pos_h_denom = (1 + ((totalTimeGap + tmp_time_hdw)/time_step));
888 pos_h = pos_h_nom/pos_h_denom;
889
890 }
891 else
892 {
893 // ---> 4.1 pos_g
894 pos_g = (pred_pos - config_.vehicleLength + ego_pos*(timeGapAndStepRatio)) / (1 + timeGapAndStepRatio);
895 // ---> 4.2 pos_h
896 double pos_h_nom = (pred_pos + ego_pos*(totalTimeGap + tmp_time_hdw)/time_step);
897 double pos_h_denom = (1 + ((totalTimeGap + tmp_time_hdw)/time_step));
898 pos_h = pos_h_nom/pos_h_denom;
899 }
900
901 // ---> 4.3 desire speed and desire location
902 double pos_des = config_.gap_weight*pos_g + (1.0 - config_.gap_weight)*pos_h;
903 // double des_spd = (pos_des - ego_pos) / time_step;
904
905 // ---> 4.4 return IHP calculated desired location
906 return pos_des;
907 }
908
909 // UCLA: find the index of the closest vehicle in the target platoon that is in front of the host vehicle (cut-in joiner).
910 // Note: The joiner will cut-in at the back of this vehicle, which make this index points to the vehicle that is leading the cut-in gap.
912 {
913 /*
914 A naive way to find the closest member that is in front of the host that point to the gap to join the platoon.
915 Note: The potential gap leading vehicle should be in front of the joiner (i.e., gap leading vehicle's dtd > joiner's dtd).
916 If the joiner is already in front of the platoon leader, this function will return -1 (i.e., cut-in front).
917 */
918
919 double min_diff = 99999.0;
920 int cut_in_index = -1; //-2 is meaningless default
921
922 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "neighbor_platoon_.size(): " << neighbor_platoon_.size());
923
924 // Loop through all target platoon members
925 for(size_t i = 0; i < neighbor_platoon_.size(); i++)
926 {
927 double current_member_dtd = neighbor_platoon_[i].vehiclePosition;
928 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "current_member_dtd: "<< current_member_dtd);
929 double curent_dtd_diff = current_member_dtd - joinerDtD;
930 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("platoon_strategic_ihp"), "curent_dtd_diff: "<< curent_dtd_diff);
931 // update min index
932 if (curent_dtd_diff > 0 && curent_dtd_diff < min_diff)
933 {
934 min_diff = current_member_dtd;
935 cut_in_index = i;
936 }
937 }
938
939 return cut_in_index;
940 }
941
942 // UCLA: find the current cut-in join gap size in downtrack distance (m). The origin of the vehicle when calculating DtD is locate at the rear axle.
943 double PlatoonManager::getCutInGap(const int gap_leading_index, const double joinerDtD)
944 {
945 /*
946 Locate the target cut-in join gap size based on the index.
947 */
948
949 // Initiate variables
950 double gap_size = -0.999;
951 size_t index = 0;
952 if (gap_leading_index >= 0)
953 {
954 index = static_cast<size_t>(gap_leading_index);
955 }
956
957 // cut-in from front
958 if (gap_leading_index == -1)
959 {
960 double gap_rear_dtd = neighbor_platoon_[0].vehiclePosition;
961 gap_size = joinerDtD - gap_rear_dtd - config_.vehicleLength;
962 }
963 // cut-in from behind
964 else if (index == neighbor_platoon_.size() - 1)
965 {
966 double gap_leading_dtd = neighbor_platoon_[index].vehiclePosition;
967 gap_size = gap_leading_dtd - joinerDtD - config_.vehicleLength;;
968 }
969 // cut-in in the middle
970 else
971 {
972 double gap_leading_dtd = neighbor_platoon_[index].vehiclePosition;
973 double gap_rear_dtd = neighbor_platoon_[index + 1].vehiclePosition;
974 gap_size = gap_leading_dtd - gap_rear_dtd - config_.vehicleLength;
975 }
976
977 // return gap_size value
978 return gap_size;
979 }
980}
double getCommandSpeed() const
Returns command speed. in m/s.
int findMaximumSpacingViolationClosestToTheHostVehicle(std::vector< double > timeHeadways) const
Find the closest vehicle to the host vehicle that violates the (time headaway) maximum spacing condit...
int getNumberOfVehicleInFront()
Get number of vehicles in front of host vehicle inside platoon.
int determineDynamicLeaderBasedOnViolation(std::vector< double > timeHeadways)
Determine the proper vehicle to follow based the time headway of each member. Note that the host will...
PlatoonMember getDynamicLeader()
Returns dynamic leader of the host vehicle.
bool removeMember(const size_t mem)
Removes a single member from the internal record of platoon members.
double getDistanceToPredVehicle()
Returns distance to the predessecor vehicle, in m.
bool removeMemberById(const std::string id)
Removes a single member from the internal record of platoon members.
PlatoonManager(std::shared_ptr< carma_ros2_utils::timers::TimerFactory > timer_factory)
Constructor.
std::vector< PlatoonMember > neighbor_platoon_
int allPredecessorFollowing()
This is the implementation of all predecessor following (APF) algorithm for leader selection in a pla...
void updateHostSpeeds(const double cmdSpeed, const double actualSpeed)
Stores the latest info on host vehicle's command & actual speeds.
void updatesOrAddMemberInfo(std::vector< PlatoonMember > &platoon, std::string senderId, double cmdSpeed, double dtDistance, double ctDistance, double curSpeed)
Updates the list of vehicles in the specified platoon, based on info available from a mobility operat...
double getPlatoonRearDowntrackDistance()
Returns downtrack distance of the rear vehicle in platoon, in m.
int getClosestIndex(double joinerDtD)
UCLA: Return joiner's desired position in terms of target platoon index to cut into the platoon....
int getHostPlatoonSize()
Returns total size of the platoon , in number of vehicles.
double getPredecessorPosition()
UCLA: Return the position of the preceding vehicle, in m.
double getCurrentDowntrackDistance() const
Returns current downtrack distance, in m.
void hostMemberUpdates(const std::string &senderId, const std::string &platoonId, const std::string &params, const double &DtD, const double &CtD)
Update information for members of the host's platoon based on a mobility operation STATUS message.
void changeFromLeaderToFollower(std::string newPlatoonId, std::string newLeaderId)
Update status when state change from Leader to Follower.
double getPlatoonFrontDowntrackDistance()
UCLA: Return the platoon leader downtrack distance, in m.
double getCutInGap(const int gap_leading_index, const double joinerDtD)
UCLA: Return the current actual gap size in the target platoon for cut-in join, in m....
void updateHostPose(const double downtrack, const double crosstrack)
Stores the latest info on location of the host vehicle.
void resetHostPlatoon()
Resets all variables that might indicate other members of the host's platoon; sets the host back to s...
bool insufficientGapWithPredecessor(double distanceToPredVehicle)
Check the gap with the predecessor vehicle.
void resetNeighborPlatoon()
Resets all variables that describe a neighbor platoon, so that no neighbor is known.
double getPredecessorSpeed()
UCLA: Return the speed of the preceding vehicle, in m/s.
double getCurrentSpeed() const
Returns current speed, in m/s.
double getCurrentCrosstrackDistance() const
Returns current crosstrack distance, in m.
double getPredecessorTimeHeadwaySum()
UCLA: Return the time headway summation of all predecessors, in s.
double getIHPDesPosFollower(double dt)
UCLA: Return follower's desired position (i.e., downtrack, in m) that maintains the desired intra-pla...
std::vector< PlatoonMember > host_platoon_
std::shared_ptr< carma_ros2_utils::timers::TimerFactory > timer_factory_
std::vector< double > getTimeHeadwayFromIndex(std::vector< double > timeHeadways, int start) const
Return a sub-vector of the platoon-wise time headaways vector that start with a given index.
std::string getHostStaticID() const
Returns current host static ID as a string.
int findLowerBoundaryViolationClosestToTheHostVehicle(std::vector< double > timeHeadways) const
Find the closest vehicle to the host vehicle that violates the (time headaway) lower boundary conditi...
std::vector< double > calculateTimeHeadway(std::vector< double > downtrackDistance, std::vector< double > speed) const
Calculate the time headaway of each platoon member and save as a vector.
void neighborMemberUpdates(const std::string &senderId, const std::string &platoonId, const std::string &params, const double &DtD, const double &CtD)
Update information for members of a neighboring platoon based on a mobility operation STATUS message.
double getCurrentPlatoonLength()
Returns overall length of the platoon. in m.
void clearActionPlan()
Resets necessary variables to indicate that the current ActionPlan is dead.
void changeFromFollowerToLeader()
Update status when state change from Follower to Leader.
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21
double ss_theta
Parameter sets for IHP platoon trajectory regulation algorithm. Please refer to the updated design do...