26#include <boost/algorithm/string.hpp>
27#include <rclcpp/logging.hpp>
53 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"Top of PlatoonManager ctor.");
60 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"Host (index " <<
hostPosInPlatoon_ <<
"): downtrack = " << downtrack <<
", crosstrack = " << crosstrack);
74 const double& DtD,
const double& CtD)
78 std::vector<std::string> inputsParams;
81 std::vector<std::string> cmd_parsed;
83 double cmdSpeed = std::stod(cmd_parsed[1]);
85 double dtDistance = DtD;
87 double ctDistance = CtD;
89 std::vector<std::string> cur_parsed;
91 double curSpeed = std::stod(cur_parsed[1]);
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);
109 if(needPlatoonIdChange)
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);
121 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"This STATUS messages is from our platoon. Updating the info...");
123 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"The first vehicle in our list is now " <<
host_platoon_[0].staticId);
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);
133 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"Host is leader: currentPlatoonID = " <<
currentPlatoonID <<
", incoming platoonId = " << platoonId);
136 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"This STATUS messages is from our platoon. Updating the info...");
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);
158 const double& DtD,
const double& CtD)
162 std::vector<std::string> inputsParams;
165 std::vector<std::string> cmd_parsed;
167 double cmdSpeed = std::stod(cmd_parsed[1]);
169 double dtDistance = DtD;
171 double ctDistance = CtD;
173 std::vector<std::string> cur_parsed;
175 double curSpeed = std::stod(cur_parsed[1]);
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);
188 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"Neighbor record is complete!");
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);
200 double dtDistance,
double ctDistance,
double curSpeed)
202 bool isExisted =
false;
203 bool sortNeeded =
false;
206 for (
size_t i = 0;
i < platoon.size(); ++
i){
207 if(platoon[
i].staticId == senderId) {
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");
214 platoon[
i].commandSpeed = cmdSpeed;
215 platoon[
i].vehiclePosition = dtDistance;
216 platoon[
i].vehicleCrossTrack = ctDistance;
217 platoon[
i].vehicleSpeed = curSpeed;
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);
228 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
" This is the HOST vehicle");
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)
242 std::string hostFlag =
" ";
248 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
" " << platoon[
i].staticId <<
"its DTD: " << platoon[
i].vehiclePosition <<
" " << hostFlag);
257 platoon.push_back(newMember);
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)
265 std::string hostFlag =
" ";
271 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
" " << platoon[
i].staticId <<
"its DTD: " << platoon[
i].vehiclePosition <<
" " << hostFlag);
280 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"host platoon size: " <<
host_platoon_.size());
390 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"host_platoon_ size: " <<
host_platoon_.size());
393 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"Leader initially set as first vehicle in platoon");
401 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"dynamic_leader_index_: " <<
dynamic_leader_index_);
404 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF output: " << dynamicLeader.
staticId);
410 RCLCPP_WARN_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"newLeaderIndex = " << newLeaderIndex <<
" is invalid coming from allPredecessorFollowing!");
419 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"Based on the output of APF algorithm we start to follow our predecessor.");
423 return dynamicLeader;
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");
441 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF algorithm did not found a dynamic leader in previous time step. Case one");
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");
473 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF calculate time headways: " );
474 for (
const auto& value : timeHeadways)
476 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF time headways: " << value);
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.");
492 for (
const auto& value : partialTimeHeadways)
494 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF partial time headways: " << value);
504 if(closestLowerBoundaryViolation == -1 && closestMaximumSpacingViolation == -1) {
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");
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);
529 }
else if(closestLowerBoundaryViolation != -1 && closestMaximumSpacingViolation == -1) {
533 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF found closestLowerBoundaryViolation on partial time headways. Case Six.");
536 }
else if(closestLowerBoundaryViolation == -1 && closestMaximumSpacingViolation != -1) {
539 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF found closestMaximumSpacingViolation on partial time headways. Case Seven.");
542 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF found closestMaximumSpacingViolation and closestLowerBoundaryViolation on partial time headways.");
543 if(closestLowerBoundaryViolation > closestMaximumSpacingViolation) {
546 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"closest LowerBoundaryViolation is higher than closestMaximumSpacingViolation on partial time headways. Case Eight.");
548 }
else if(closestLowerBoundaryViolation < closestMaximumSpacingViolation) {
551 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"closestMaximumSpacingViolation is higher than closestLowerBoundaryViolation on partial time headways. Case Nine.");
554 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF dynamic Leader selection parameter is wrong!");
565 std::vector<double> result(timeHeadways.begin() + start-1, timeHeadways.end());
579 bool frontGapIsNotLargeEnough = distanceToPredVehicle <
config_.
maxCutinGap && previousLeaderIsPredecessor;
581 return (frontGapIsTooSmall || frontGapIsNotLargeEnough);
586 std::vector<double> timeHeadways(downtrackDistance.size() - 1);
588 for (
size_t i = 0;
i < timeHeadways.size();
i++){
592 timeHeadways[
i] = (downtrackDistance[
i] - downtrackDistance[
i+1]) / speed[
i+1];
597 timeHeadways[
i] = std::numeric_limits<double>::infinity();
624 if(closestLowerBoundaryViolation > closestMaximumSpacingViolation) {
625 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF found violation on closestLowerBoundaryViolation at " << closestLowerBoundaryViolation);
626 return closestLowerBoundaryViolation;
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;
633 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"APF found no violations on both closestLowerBoundaryViolation and closestMaximumSpacingViolation");
641 for(
int i = timeHeadways.size()-1;
i >= 0;
i--) {
660 for(
int i = timeHeadways.size()-1;
i >= 0 ;
i--) {
661 if(timeHeadways[
i] > maxAllowableHeadaway_adjusted)
683 RCLCPP_WARN(rclcpp::get_logger(
"platoon_strategic_ihp"),
"### Host becoming leader, but is already at index 0 in host_platoon_ vector! Vector unchanged.");
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);
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);
786 double tmp_time_hdw = 0.0;
788 for (
size_t index = 0; index < downtrackDistance.size(); index++)
790 cur_dtd = downtrackDistance[index];
844 double tmp_time_hdw = 0.0;
846 for (
size_t index = 0; index < downtrackDistance.size(); index++)
848 cur_dtd = downtrackDistance[index];
877 double timeGapAndStepRatio = desirePlatoonGap/time_step;
878 double totalTimeGap = desirePlatoonGap*pos_idx;
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;
894 pos_g = (pred_pos -
config_.
vehicleLength + ego_pos*(timeGapAndStepRatio)) / (1 + timeGapAndStepRatio);
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;
919 double min_diff = 99999.0;
920 int cut_in_index = -1;
922 RCLCPP_DEBUG_STREAM(rclcpp::get_logger(
"platoon_strategic_ihp"),
"neighbor_platoon_.size(): " <<
neighbor_platoon_.size());
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);
932 if (curent_dtd_diff > 0 && curent_dtd_diff < min_diff)
934 min_diff = current_member_dtd;
950 double gap_size = -0.999;
952 if (gap_leading_index >= 0)
954 index =
static_cast<size_t>(gap_leading_index);
958 if (gap_leading_index == -1)
std::string platoonLeaderID
std::string neighborPlatoonID
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 previousFunctionalDynamicLeaderIndex_
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.
size_t neighbor_platoon_info_size_
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::string HostMobilityId
std::string algorithmType_
std::vector< PlatoonMember > neighbor_platoon_
std::string previousFunctionalDynamicLeaderID_
size_t dynamic_leader_index_
int allPredecessorFollowing()
This is the implementation of all predecessor following (APF) algorithm for leader selection in a pla...
std::string currentPlatoonID
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.
PlatoonPluginConfig config_
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.
bool is_neighbor_record_complete_
double getPredecessorPosition()
UCLA: Return the position of the preceding vehicle, in m.
double getCurrentDowntrackDistance() const
Returns current downtrack distance, in m.
std::string neighbor_platoon_leader_id_
void hostMemberUpdates(const std::string &senderId, const std::string &platoonId, const std::string ¶ms, 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.
std::string targetPlatoonID
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.
const std::string dummyID
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 ¶ms, 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
double ss_theta
Parameter sets for IHP platoon trajectory regulation algorithm. Please refer to the updated design do...
double significantDTDchange
double minAllowableHeadaway
double headawayStableUpperBond
double headawayStableLowerBond
double maxAllowableHeadaway