27#include <carma_v2x_msgs/msg/mobility_operation.hpp>
28#include <carma_v2x_msgs/msg/mobility_request.hpp>
29#include <carma_v2x_msgs/msg/mobility_response.hpp>
30#include <carma_v2x_msgs/msg/plan_type.hpp>
31#include <geometry_msgs/msg/pose_stamped.hpp>
32#include <geometry_msgs/msg/twist_stamped.hpp>
35#include <boost/uuid/uuid_generators.hpp>
36#include <boost/uuid/uuid_io.hpp>
37#include <carma_ros2_utils/timers/TimerFactory.hpp>
129 PlatooningManager(std::shared_ptr<carma_ros2_utils::timers::TimerFactory> timer_factory);
137 void updateHostPose(
const double downtrack,
const double crosstrack);
156 void hostMemberUpdates(
const std::string& senderId,
const std::string& platoonId,
const std::string& params,
157 const double& DtD,
const double& CtD);
168 void neighborMemberUpdates(
const std::string& senderId,
const std::string& platoonId,
const std::string& params,
169 const double& DtD,
const double& CtD);
185 double dtDistance,
double ctDistance,
double curSpeed);
356 double getCutInGap(
const int gap_leading_index,
const double joinerDtD);
358 const std::string
dummyID =
"00000000-0000-0000-0000-000000000000";
458 std::vector<double>
calculateTimeHeadway(std::vector<double> downtrackDistance, std::vector<double> speed)
const;
Class containing the logic for platoon manager. It is responsible for keeping track of the platoon me...
bool is_neighbor_record_complete_
void clearActionPlan()
Resets necessary variables to indicate that the current ActionPlan is dead.
std::vector< PlatoonMember > neighbor_platoon_
int previousFunctionalDynamicLeaderIndex_
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....
double getIHPDesPosFollower(double dt)
UCLA: Return follower's desired position (i.e., downtrack, in m) that maintains the desired intra-pla...
std::string currentPlatoonID
double downtrack_progress_
double getPredecessorTimeHeadwaySum()
UCLA: Return the time headway summation of all predecessors, in s.
double getPredecessorSpeed()
UCLA: Return the speed of the preceding vehicle, in m/s.
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.
int findLowerBoundaryViolationClosestToTheHostVehicle(std::vector< double > timeHeadways) const
Find the closest vehicle to the host vehicle that violates the (time headaway) lower boundary conditi...
bool insufficientGapWithPredecessor(double distanceToPredVehicle)
Check the gap with the predecessor vehicle.
std::string neighborPlatoonID
int determineDynamicLeaderBasedOnViolation(std::vector< double > timeHeadways)
Determine the proper vehicle to follow based the time headway of each member. Note that the host will...
std::string algorithmType_
int getHostPlatoonSize()
Returns total size of the platoon , in number of vehicles.
void resetNeighborPlatoon()
Resets all variables that describe a neighbor platoon, so that no neighbor is known.
void resetHostPlatoon()
Resets all variables that might indicate other members of the host's platoon; sets the host back to s...
bool removeMember(const size_t mem)
Removes a single member from the internal record of platoon members.
void updateHostPose(const double downtrack, const double crosstrack)
Stores the latest info on location of the host vehicle.
std::string OPERATION_STATUS_TYPE
int getClosestIndex(double joinerDtD)
UCLA: Return joiner's desired position in terms of target platoon index to cut into the platoon....
size_t dynamic_leader_index_
int findMaximumSpacingViolationClosestToTheHostVehicle(std::vector< double > timeHeadways) const
Find the closest vehicle to the host vehicle that violates the (time headaway) maximum spacing condit...
std::string MOBILITY_STRATEGY
PlatooningPluginConfig config_
void updateHostSpeeds(const double cmdSpeed, const double actualSpeed)
Stores the latest info on host vehicle's command & actual speeds.
double getDistanceToPredVehicle()
Returns distance to the predessecor vehicle, in m.
PlatooningManager(std::shared_ptr< carma_ros2_utils::timers::TimerFactory > timer_factory)
Constructor.
int getNumberOfVehicleInFront()
Get number of vehicles in front of host vehicle inside platoon.
std::string HostMobilityId
std::vector< PlatoonMember > host_platoon_
double getPredecessorPosition()
UCLA: Return the position of the preceding vehicle, in m.
double getPlatoonRearDowntrackDistance()
Returns downtrack distance of the rear vehicle in platoon, in m.
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.
void changeFromLeaderToFollower(std::string newPlatoonId, std::string newLeaderId)
Update status when state change from Leader to Follower.
std::string OPERATION_INFO_TYPE
std::shared_ptr< carma_ros2_utils::timers::TimerFactory > timer_factory_
size_t neighbor_platoon_info_size_
bool removeMemberById(const std::string id)
Removes a single member from the internal record of platoon members.
const std::string dummyID
PlatoonMember getDynamicLeader()
Returns dynamic leader of the host vehicle.
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...
PlatoonState current_platoon_state
std::string platoonLeaderID
double getCurrentSpeed() const
Returns current speed, in m/s.
geometry_msgs::msg::PoseStamped pose_msg_
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 changeFromFollowerToLeader()
Update status when state change from Follower to Leader.
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.
std::string getHostStaticID() const
Returns current host static ID as a string.
double getPlatoonFrontDowntrackDistance()
UCLA: Return the platoon leader downtrack distance, in m.
double getCurrentPlatoonLength()
Returns overall length of the platoon. in m.
std::string previousFunctionalDynamicLeaderID_
std::string JOIN_AT_REAR_PARAMS
double getCommandSpeed() const
Returns command speed. in m/s.
std::string JOIN_FROM_FRONT_PARAMS
double getCurrentCrosstrackDistance() const
Returns current crosstrack distance, in m.
double getCurrentDowntrackDistance() const
Returns current downtrack distance, in m.
std::string targetPlatoonID
int allPredecessorFollowing()
This is the implementation of all predecessor following (APF) algorithm for leader selection in a pla...
std::string neighbor_platoon_leader_id_
MobilityRequestResponse
A response to an MobilityRequest message. ACK - indicates that the plugin accepts the MobilityRequest...
PlatoonState
Platoon States. UCLA: Added additional states (i.e., LEADERABORTING and CANDIDATELEADER) for same-lan...
Struct for an action plan, which describes a transient joining activity.
ActionPlan(bool valid, unsigned long planStartTime, std::string planId, std::string peerId)
unsigned long planStartTime
PlatoonMember(std::string staticId, double commandSpeed, double vehicleSpeed, double vehiclePosition, double vehicleCrossTrack, long timestamp)
Stuct containing the algorithm configuration values for the yield_pluginConfig.