Eclipse SUMO - Simulation of Urban MObility
MSAbstractLaneChangeModel.h
Go to the documentation of this file.
1 /****************************************************************************/
2 // Eclipse SUMO, Simulation of Urban MObility; see https://eclipse.dev/sumo
3 // Copyright (C) 2001-2024 German Aerospace Center (DLR) and others.
4 // This program and the accompanying materials are made available under the
5 // terms of the Eclipse Public License 2.0 which is available at
6 // https://www.eclipse.org/legal/epl-2.0/
7 // This Source Code may also be made available under the following Secondary
8 // Licenses when the conditions for such availability set forth in the Eclipse
9 // Public License 2.0 are satisfied: GNU General Public License, version 2
10 // or later which is available at
11 // https://www.gnu.org/licenses/old-licenses/gpl-2.0-standalone.html
12 // SPDX-License-Identifier: EPL-2.0 OR GPL-2.0-or-later
13 /****************************************************************************/
23 // Interface for lane-change models
24 /****************************************************************************/
25 #pragma once
26 #include <config.h>
27 
28 #include <microsim/MSGlobals.h>
29 #include <microsim/MSLeaderInfo.h>
30 #include <microsim/MSVehicle.h>
31 
32 
33 // ===========================================================================
34 // class declarations
35 // ===========================================================================
36 class MSLane;
37 class SUMOSAXAttributes;
38 
39 
40 // ===========================================================================
41 // class definitions
42 // ===========================================================================
48 public:
49 
53  class MSLCMessager {
54  public:
60  MSLCMessager(MSVehicle* leader, MSVehicle* neighLead, MSVehicle* neighFollow)
61  : myLeader(leader), myNeighLeader(neighLead),
62  myNeighFollower(neighFollow) { }
63 
64 
67 
68 
74  void* informLeader(void* info, MSVehicle* sender) {
75  assert(myLeader != 0);
76  return myLeader->getLaneChangeModel().inform(info, sender);
77  }
78 
79 
85  void* informNeighLeader(void* info, MSVehicle* sender) {
86  assert(myNeighLeader != 0);
87  return myNeighLeader->getLaneChangeModel().inform(info, sender);
88  }
89 
90 
96  void* informNeighFollower(void* info, MSVehicle* sender) {
97  assert(myNeighFollower != 0);
98  return myNeighFollower->getLaneChangeModel().inform(info, sender);
99  }
100 
101 
102  private:
109 
110  };
111 
112  struct StateAndDist {
113  // @brief LaneChangeAction flags
114  int state;
115  // @brief Lateral distance to be completed in the next step
116  double latDist;
117  // @brief Full lateral distance required for the completion of the envisioned maneuver
118  double maneuverDist;
119  // @brief direction that was checked
120  int dir;
121 
122  StateAndDist(int _state, double _latDist, double _targetDist, int _dir) :
123  state(_state),
124  latDist(_latDist),
125  maneuverDist(_targetDist),
126  dir(_dir) {}
127 
128  bool sameDirection(const StateAndDist& other) const {
129  return latDist * other.latDist > 0;
130  }
131  };
132 
134  void static initGlobalOptions(const OptionsCont& oc);
135 
141 
145  virtual LaneChangeModel getModelID() const = 0;
146 
155  virtual int checkChangeBeforeCommitting(const MSVehicle* veh, int state) const {
156  UNUSED_PARAMETER(veh);
157  UNUSED_PARAMETER(state);
158  return 0;
159  }
160 
164  virtual void saveState(OutputDevice& out) const;
165 
169  virtual void loadState(const SUMOSAXAttributes& attrs);
170 
172  static bool haveLCOutput() {
173  return myLCOutput;
174  }
175 
177  static bool outputLCStarted() {
178  return myLCStartedOutput;
179  }
180 
182  static bool outputLCEnded() {
183  return myLCEndedOutput;
184  }
185 
191 
193  virtual ~MSAbstractLaneChangeModel();
194 
195  inline int getOwnState() const {
196  return myOwnState;
197  }
198 
199  inline int getPrevState() const {
201  return myPreviousState2;
202  }
203 
204  virtual void setOwnState(const int state);
205 
207  void setManeuverDist(const double dist);
209  double getManeuverDist() const;
210  double getPreviousManeuverDist() const;
211 
213  virtual void updateSafeLatDist(const double travelledLatDist);
214 
215  const std::pair<int, int>& getSavedState(const int dir) const {
216  if (dir == -1) {
217  return mySavedStateRight;
218  } else if (dir == 0) {
219  return mySavedStateCenter;
220  } else {
221  return mySavedStateLeft;
222  }
223  }
224 
225  void saveLCState(const int dir, int stateWithoutTraCI, const int state) {
226  int canceledStrategic = getCanceledState(dir);
227  // avoid conflicting directions
228  if ((canceledStrategic & LCA_WANTS_LANECHANGE_OR_STAY) != 0) {
229  stateWithoutTraCI = canceledStrategic;
230  }
231  const auto pair = std::make_pair(stateWithoutTraCI, state);
232  if (dir == -1) {
233  mySavedStateRight = pair;
234  } else if (dir == 0) {
235  mySavedStateCenter = pair;
236  } else {
237  mySavedStateLeft = pair;
238  }
239  }
240 
243  void saveNeighbors(const int dir, const MSLeaderDistanceInfo& followers, const MSLeaderDistanceInfo& leaders);
244 
247  void saveNeighbors(const int dir, const std::pair<MSVehicle* const, double>& follower, const std::pair<MSVehicle* const, double>& leader);
248 
250  void clearNeighbors();
251 
253  const std::shared_ptr<MSLeaderDistanceInfo> getFollowers(const int dir);
254 
256  const std::shared_ptr<MSLeaderDistanceInfo> getLeaders(const int dir);
257 
258  int& getCanceledState(const int dir) {
259  if (dir == -1) {
260  return myCanceledStateRight;
261  } else if (dir == 0) {
262  return myCanceledStateCenter;
263  } else {
264  return myCanceledStateLeft;
265  }
266  }
267 
269  bool isStrategicBlocked() const;
270 
271  void setFollowerGaps(CLeaderDist follower, double secGap);
272  void setLeaderGaps(CLeaderDist, double secGap);
273  void setOrigLeaderGaps(CLeaderDist, double secGap);
274  void setFollowerGaps(const MSLeaderDistanceInfo& vehicles);
275  void setLeaderGaps(const MSLeaderDistanceInfo& vehicles);
276  void setOrigLeaderGaps(const MSLeaderDistanceInfo& vehicles);
277 
278  virtual void prepareStep();
279 
284  virtual int wantsChange(
285  int laneOffset,
286  MSAbstractLaneChangeModel::MSLCMessager& msgPass, int blocked,
287  const std::pair<MSVehicle*, double>& leader,
288  const std::pair<MSVehicle*, double>& follower,
289  const std::pair<MSVehicle*, double>& neighLead,
290  const std::pair<MSVehicle*, double>& neighFollow,
291  const MSLane& neighLane,
292  const std::vector<MSVehicle::LaneQ>& preb,
293  MSVehicle** lastBlocked,
294  MSVehicle** firstBlocked) {
295  UNUSED_PARAMETER(laneOffset);
296  UNUSED_PARAMETER(&msgPass);
297  UNUSED_PARAMETER(blocked);
298  UNUSED_PARAMETER(&leader);
299  UNUSED_PARAMETER(&follower);
300  UNUSED_PARAMETER(&neighLead);
301  UNUSED_PARAMETER(&neighFollow);
302  UNUSED_PARAMETER(&neighLane);
303  UNUSED_PARAMETER(&preb);
304  UNUSED_PARAMETER(lastBlocked);
305  UNUSED_PARAMETER(firstBlocked);
306  throw ProcessError("Method not implemented by model " + toString(myModel));
307  };
308 
309  virtual int wantsChangeSublane(
310  int laneOffset,
311  LaneChangeAction alternatives,
312  const MSLeaderDistanceInfo& leaders,
313  const MSLeaderDistanceInfo& followers,
314  const MSLeaderDistanceInfo& blockers,
315  const MSLeaderDistanceInfo& neighLeaders,
316  const MSLeaderDistanceInfo& neighFollowers,
317  const MSLeaderDistanceInfo& neighBlockers,
318  const MSLane& neighLane,
319  const std::vector<MSVehicle::LaneQ>& preb,
320  MSVehicle** lastBlocked,
321  MSVehicle** firstBlocked,
322  double& latDist, double& targetDistLat, int& blocked) {
323  UNUSED_PARAMETER(laneOffset);
324  UNUSED_PARAMETER(alternatives);
325  UNUSED_PARAMETER(&leaders);
326  UNUSED_PARAMETER(&followers);
327  UNUSED_PARAMETER(&blockers);
328  UNUSED_PARAMETER(&neighLeaders);
329  UNUSED_PARAMETER(&neighFollowers);
330  UNUSED_PARAMETER(&neighBlockers);
331  UNUSED_PARAMETER(&neighLane);
332  UNUSED_PARAMETER(&preb);
333  UNUSED_PARAMETER(lastBlocked);
334  UNUSED_PARAMETER(firstBlocked);
335  UNUSED_PARAMETER(latDist);
336  UNUSED_PARAMETER(targetDistLat);
337  UNUSED_PARAMETER(blocked);
338  throw ProcessError("Method not implemented by model " + toString(myModel));
339  }
340 
342  virtual void updateExpectedSublaneSpeeds(const MSLeaderDistanceInfo& ahead, int sublaneOffset, int laneIndex) {
343  UNUSED_PARAMETER(&ahead);
344  UNUSED_PARAMETER(sublaneOffset);
345  UNUSED_PARAMETER(laneIndex);
346  throw ProcessError("Method not implemented by model " + toString(myModel));
347  }
348 
351  UNUSED_PARAMETER(sd1);
352  UNUSED_PARAMETER(sd2);
353  throw ProcessError("Method not implemented by model " + toString(myModel));
354  }
355 
356  virtual void* inform(void* info, MSVehicle* sender) = 0;
357 
371  virtual double patchSpeed(const double min, const double wanted, const double max,
372  const MSCFModel& cfModel) = 0;
373 
374  /* @brief called once when the primary lane of the vehicle changes (updates
375  * the custom variables of each child implementation */
376  virtual void changed() = 0;
377 
378  /* @brief called once when the vehicle moves to a new lane in an "irregular" way (i.e. by teleporting)
379  * resets custom variables of each child implementation */
380  virtual void resetState() {};
381 
383  virtual double getSafetyFactor() const {
384  return 1.0;
385  }
386 
388  virtual double getOppositeSafetyFactor() const {
389  return 1.0;
390  }
391 
393  virtual bool debugVehicle() const {
394  return false;
395  }
396 
398  void changedToOpposite();
399 
400  void unchanged() {
401  if (myLastLaneChangeOffset > 0) {
403  } else if (myLastLaneChangeOffset < 0) {
405  }
406  }
407 
412  return myShadowLane;
413  }
414 
416  MSLane* getShadowLane(const MSLane* lane) const;
417 
419  MSLane* getShadowLane(const MSLane* lane, double posLat) const;
420 
421  const std::vector<MSLane*>& getShadowFurtherLanes() const {
422  return myShadowFurtherLanes;
423  }
424 
425  const std::vector<double>& getShadowFurtherLanesPosLat() const {
427  }
428 
433  return myTargetLane;
434  }
435 
436  const std::vector<MSLane*>& getFurtherTargetLanes() const {
437  return myFurtherTargetLanes;
438  }
439 
441  return myLastLaneChangeOffset;
442  }
443 
444 
446  inline bool pastMidpoint() const {
447  return myLaneChangeCompletion >= 0.5;
448  }
449 
451  SUMOTime remainingTime() const;
452 
464  virtual double estimateLCDuration(const double speed, const double remainingManeuverDist, const double decel, bool urgent) const;
465 
467  inline bool isChangingLanes() const {
468  return myLaneChangeCompletion < (1 - NUMERICAL_EPS);
469  }
470 
472  inline double getLaneChangeCompletion() const {
473  return myLaneChangeCompletion;
474  }
475 
477  inline int getLaneChangeDirection() const {
478  return myLaneChangeDirection;
479  }
480 
482  int getShadowDirection() const;
483 
485  double calcAngleOffset();
486 
488  inline double getAngleOffset() const {
489  return myAngleOffset;
490  }
491 
493  inline void setAngleOffset(const double angleOffset) {
494  myAngleOffset = angleOffset;
495  }
496 
498  inline void setPreviousAngleOffset(const double angleOffset) {
499  myPreviousAngleOffset = angleOffset;
500  }
501 
503  inline bool alreadyChanged() const {
504  return myAlreadyChanged;
505  }
506 
508  void resetChanged() {
509  myAlreadyChanged = false;
510  }
511 
513  bool startLaneChangeManeuver(MSLane* source, MSLane* target, int direction);
514 
516  void memorizeGapsAtLCInit();
517  void clearGapsAtLCInit();
518 
519  /* @brief continue the lane change maneuver and return whether the midpoint
520  * was passed in this step
521  */
522  bool updateCompletion();
523 
524  /* @brief update lane change shadow after the vehicle moved to a new lane */
525  void updateShadowLane();
526 
527  /* @brief update lane change reservations after the vehicle moved to a new lane
528  * @note The shadow lane should always be updated before updating the target lane. */
530 
531  /* @brief Determines the lane which the vehicle intends to enter during its current action step.
532  * targetDir is set to the offset of the returned lane with respect to the vehicle'a current lane. */
533  MSLane* determineTargetLane(int& targetDir) const;
534 
535  /* @brief finish the lane change maneuver
536  */
538 
539  /* @brief clean up all references to the shadow vehicle
540  */
541  void cleanupShadowLane();
542 
543  /* @brief clean up all references to the vehicle on its target lanes
544  */
545  void cleanupTargetLane();
546 
548  virtual bool saveBlockerLength(double /* length */, double /* foeLeftSpace */) {
549  return true;
550  }
551 
553  myPartiallyOccupatedByShadow.push_back(lane);
554  }
555 
557  myNoPartiallyOccupatedByShadow.push_back(lane);
558  }
559 
561  void primaryLaneChanged(MSLane* source, MSLane* target, int direction);
562 
564  void laneChangeOutput(const std::string& tag, MSLane* source, MSLane* target, int direction, double maneuverDist = 0);
565 
567  virtual bool sublaneChangeCompleted(const double latDist) const {
568  UNUSED_PARAMETER(latDist);
569  throw ProcessError("Method not implemented by model " + toString(myModel));
570  }
571 
573  void setShadowApproachingInformation(MSLink* link) const;
575 
576  bool isOpposite() const {
577  return myAmOpposite;
578  }
579 
582 
583  double getCommittedSpeed() const {
584  return myCommittedSpeed;
585  }
586 
588  double getSpeedLat() const {
589  return mySpeedLat;
590  }
591 
592  /* @brief reset the angle (in case no lane changing happens in this step
593  * and the maneuver was finished in the previous step) */
594  virtual void resetSpeedLat();
595 
597  double getAccelerationLat() const {
598  return myAccelerationLat;
599  }
600 
602  void setSpeedLat(double speedLat);
603 
606  virtual double computeSpeedLat(double latDist, double& maneuverDist, bool urgent) const;
607 
610  virtual double getAssumedDecelForLaneChangeDuration() const;
611 
613  virtual std::string getParameter(const std::string& key) const {
614  throw InvalidArgument("Parameter '" + key + "' is not supported for laneChangeModel of type '" + toString(myModel) + "'");
615  }
616 
618  virtual void setParameter(const std::string& key, const std::string& value) {
619  UNUSED_PARAMETER(value);
620  throw InvalidArgument("Setting parameter '" + key + "' is not supported for laneChangeModel of type '" + toString(myModel) + "'");
621  }
622 
624  virtual double getExtraReservation(int /*bestLaneOffset*/) const {
625  return 0;
626  }
627 
630  void checkTraCICommands();
631 
633  double getForwardPos() const;
634 
635  bool hasBlueLight() const {
636  return myHaveBlueLight;
637  }
638 
641  }
642 
643  static const double NO_NEIGHBOR;
644 
645 protected:
646  virtual bool congested(const MSVehicle* const neighLeader);
647 
648  virtual bool predInteraction(const std::pair<MSVehicle*, double>& leader);
649 
650  virtual bool avoidOvertakeRight() const;
651 
653  bool cancelRequest(int state, int laneOffset);
654 
656  double getMaxSpeedLat2() const;
657 
664  void addLCSpeedAdvice(const double vSafe, bool ownAdvice = true);
665 
666 
667 protected:
670 
677 
678  std::pair<int, int> mySavedStateRight;
679  std::pair<int, int> mySavedStateCenter;
680  std::pair<int, int> mySavedStateLeft;
684 
687  std::shared_ptr<MSLeaderDistanceInfo> myLeftFollowers;
688  std::shared_ptr<MSLeaderDistanceInfo> myLeftLeaders;
689  std::shared_ptr<MSLeaderDistanceInfo> myRightFollowers;
690  std::shared_ptr<MSLeaderDistanceInfo> myRightLeaders;
692 
694  double mySpeedLat;
695 
698 
701 
704 
707 
710 
713 
716 
719  /* @brief Lanes that are partially (laterally) occupied by the back of the
720  * vehicle (analogue to MSVehicle::myFurtherLanes) */
721  std::vector<MSLane*> myShadowFurtherLanes;
722  std::vector<double> myShadowFurtherLanesPosLat;
723 
724 
733 
734  /* @brief Further upstream lanes that are affected by the vehicle's maneuver (analogue to MSVehicle::myFurtherLanes)
735  * @note If myTargetLane==nullptr, we may assume myFurtherTargetLanes.size()==0, otherwise we have
736  * myFurtherTargetLanes.size() == myVehicle.getFurtherLanes.size()
737  * Here it may occur that an element myFurtherTargetLanes[i]==nullptr if myFurtherLanes[i] has
738  * no parallel lane in the change direction.
739  * */
740  std::vector<MSLane*> myFurtherTargetLanes;
741 
743  inline const MSCFModel& getCarFollowModel() const {
744  return myVehicle.getCarFollowModel();
745  }
746 
749 
751  std::vector<MSLane*> myPartiallyOccupatedByShadow;
752 
753  /* @brief list of lanes where there is no shadow vehicle partial occupator
754  * (when changing to a lane that has no predecessor) */
755  std::vector<MSLane*> myNoPartiallyOccupatedByShadow;
756 
760 
774 
778 
779  // @brief the maximum lateral speed for non-strategic changes when standing
781  // @brief the factor of maximum lateral speed to longitudinal speed for non-strategic changes
783  // @brief the maximum lateral maneuver distance when standing
785  // @brief factor for lane keeping imperfection
786  double mySigma;
787  // allow overtaking right even though it is prohibited
789 
792 
793  /* @brief to be called by derived classes in their changed() method.
794  * If dir=0 is given, the current value remains unchanged */
795  void initLastLaneChangeOffset(int dir);
796 
797  /* @brief vector of LC-related acceleration recommendations combined with a
798  * boolean to indicate whether the advice is from ego or someone else.
799  * Filled in wantsChange() and applied in patchSpeed() */
800  std::vector<std::pair<double, bool> > myLCAccelerationAdvices;
801 
804 
806  static bool myLCOutput;
807  static bool myLCStartedOutput;
808  static bool myLCEndedOutput;
809  static bool myLCXYOutput;
810 
811 
812 private:
813  /* @brief information how long ago the vehicle has performed a lane-change,
814  * sign indicates direction of the last change
815  */
817 
819  mutable std::vector<MSLink*> myApproachedByShadow;
820 
823 
827 
830 
831 
832 private:
835 };
long long int SUMOTime
Definition: GUI.h:35
std::pair< const MSVehicle *, double > CLeaderDist
Definition: MSLeaderInfo.h:32
SUMOTime DELTA_T
Definition: SUMOTime.cpp:38
LatAlignmentDefinition
Possible ways to choose the lateral alignment, i.e., how vehicles align themselves within their lane.
LaneChangeAction
The state of a vehicle's lane-change behavior.
@ LCA_WANTS_LANECHANGE_OR_STAY
lane can change or stay
LaneChangeModel
#define UNUSED_PARAMETER(x)
Definition: StdDefs.h:30
std::string toString(const T &t, std::streamsize accuracy=gPrecision)
Definition: ToString.h:46
A class responsible for exchanging messages between cars involved in lane-change interaction.
MSVehicle * myNeighFollower
The follower on the lane the vehicle want to change to.
void * informNeighFollower(void *info, MSVehicle *sender)
Informs the follower on the desired lane.
void * informLeader(void *info, MSVehicle *sender)
Informs the leader on the same lane.
void * informNeighLeader(void *info, MSVehicle *sender)
Informs the leader on the desired lane.
MSLCMessager(MSVehicle *leader, MSVehicle *neighLead, MSVehicle *neighFollow)
Constructor.
MSVehicle * myNeighLeader
The leader on the lane the vehicle want to change to.
MSVehicle * myLeader
The leader on the informed vehicle's lane.
Interface for lane-change models.
double getLaneChangeCompletion() const
Get the current lane change completion ratio.
double getForwardPos() const
get vehicle position relative to the forward direction lane
virtual std::string getParameter(const std::string &key) const
try to retrieve the given parameter from this laneChangeModel. Throw exception for unsupported key
void setShadowPartialOccupator(MSLane *lane)
double myAccelerationLat
the current lateral acceleration
void setFollowerGaps(CLeaderDist follower, double secGap)
const MSCFModel & getCarFollowModel() const
The vehicle's car following model.
std::vector< MSLane * > myFurtherTargetLanes
bool myAlreadyChanged
whether the vehicle has already moved this step
bool myAmOpposite
whether the vehicle is driving in the opposite direction
std::shared_ptr< MSLeaderDistanceInfo > myRightFollowers
std::pair< int, int > mySavedStateCenter
std::shared_ptr< MSLeaderDistanceInfo > myRightLeaders
virtual void setOwnState(const int state)
bool pastMidpoint() const
return whether the vehicle passed the midpoint of a continuous lane change maneuver
const std::vector< double > & getShadowFurtherLanesPosLat() const
double myPreviousAngleOffset
the angle offset of the previous time step resulting from lane change and sigma
virtual double getAssumedDecelForLaneChangeDuration() const
Returns a deceleration value which is used for the estimation of the duration of a lane change.
virtual double computeSpeedLat(double latDist, double &maneuverDist, bool urgent) const
decides the next lateral speed depending on the remaining lane change distance to be covered and upda...
virtual double estimateLCDuration(const double speed, const double remainingManeuverDist, const double decel, bool urgent) const
Calculates the maximal time needed to complete a lane change maneuver if lcMaxSpeedLatFactor and lcMa...
std::shared_ptr< MSLeaderDistanceInfo > myLeftLeaders
int myPreviousState
lane changing state from the previous simulation step
static bool outputLCEnded()
whether start of maneuvers shall be recorede
double getManeuverDist() const
Returns the remaining unblocked distance for the current maneuver. (only used by sublane model)
int getLaneChangeDirection() const
return the direction of the current lane change maneuver
int myOwnState
The current state of the vehicle.
double myLastOrigLeaderGap
acutal and secure distance to closest leader vehicle on the original when performing lane change
virtual bool predInteraction(const std::pair< MSVehicle *, double > &leader)
void laneChangeOutput(const std::string &tag, MSLane *source, MSLane *target, int direction, double maneuverDist=0)
called once the vehicle ends a lane change manoeuvre (non-instant)
bool myDontResetLCGaps
Flag to prevent resetting the memorized values for LC relevant gaps until the LC output is triggered ...
void resetChanged()
reset the flag whether a vehicle already moved to false
int myPreviousState2
lane changing state from step before the previous simulation step
const std::shared_ptr< MSLeaderDistanceInfo > getFollowers(const int dir)
Returns the neighboring, lc-relevant followers for the last step in the requested direction.
void setAngleOffset(const double angleOffset)
set the angle offset resulting from lane change and sigma
double myCommittedSpeed
the speed when committing to a change maneuver
MSLane * getShadowLane() const
Returns the lane the vehicle's shadow is on during continuous/sublane lane change.
virtual LatAlignmentDefinition getDesiredAlignment() const
std::pair< int, int > mySavedStateLeft
std::shared_ptr< MSLeaderDistanceInfo > myLeftFollowers
Cached info on lc-relevant neighboring vehicles.
static bool myLCOutput
whether to record lane-changing
bool startLaneChangeManeuver(MSLane *source, MSLane *target, int direction)
start the lane change maneuver and return whether it continues
virtual double getExtraReservation(int) const
reserve extra space for unseen blockers when more tnan one lane change is required
virtual void saveState(OutputDevice &out) const
Save the state of the laneChangeModel.
std::pair< int, int > mySavedStateRight
std::vector< MSLane * > myPartiallyOccupatedByShadow
list of lanes where the shadow vehicle is partial occupator
double myLastLeaderSecureGap
the minimum longitudinal distances to vehicles on the target lane that would be necessary for stringe...
void endLaneChangeManeuver(const MSMoveReminder::Notification reason=MSMoveReminder::NOTIFICATION_LANE_CHANGE)
virtual double getSafetyFactor() const
return factor for modifying the safety constraints of the car-following model
void saveLCState(const int dir, int stateWithoutTraCI, const int state)
static bool myAllowOvertakingRight
whether overtaking on the right is permitted
bool myHaveBlueLight
whether this vehicle is driving with special permissions and behavior
virtual bool saveBlockerLength(double, double)
reserve space at the end of the lane to avoid dead locks
std::vector< MSLink * > myApproachedByShadow
links which are approached by the shadow vehicle
static bool haveLCOutput()
whether lanechange-output is active
virtual void updateExpectedSublaneSpeeds(const MSLeaderDistanceInfo &ahead, int sublaneOffset, int laneIndex)
update expected speeds for each sublane of the current edge
void addLCSpeedAdvice(const double vSafe, bool ownAdvice=true)
Takes a vSafe (speed advice for speed in the next simulation step), converts it into an acceleration ...
virtual void * inform(void *info, MSVehicle *sender)=0
virtual int wantsChange(int laneOffset, MSAbstractLaneChangeModel::MSLCMessager &msgPass, int blocked, const std::pair< MSVehicle *, double > &leader, const std::pair< MSVehicle *, double > &follower, const std::pair< MSVehicle *, double > &neighLead, const std::pair< MSVehicle *, double > &neighFollow, const MSLane &neighLane, const std::vector< MSVehicle::LaneQ > &preb, MSVehicle **lastBlocked, MSVehicle **firstBlocked)
Called to examine whether the vehicle wants to change using the given laneOffset. This method gets th...
virtual double getOppositeSafetyFactor() const
return factor for modifying the safety constraints for opposite-diretction overtaking of the car-foll...
void setLeaderGaps(CLeaderDist, double secGap)
const std::shared_ptr< MSLeaderDistanceInfo > getLeaders(const int dir)
Returns the neighboring, lc-relevant leaders for the last step in the requested direction.
std::vector< MSLane * > myNoPartiallyOccupatedByShadow
MSAbstractLaneChangeModel & operator=(const MSAbstractLaneChangeModel &s)
Invalidated assignment operator.
const std::vector< MSLane * > & getShadowFurtherLanes() const
const std::pair< int, int > & getSavedState(const int dir) const
void setNoShadowPartialOccupator(MSLane *lane)
const LaneChangeModel myModel
the type of this model
bool cancelRequest(int state, int laneOffset)
whether the influencer cancels the given request
double myLastLeaderGap
the actual minimum longitudinal distances to vehicles on the target lane
SUMOTime remainingTime() const
Compute the remaining time until LC completion.
virtual LaneChangeModel getModelID() const =0
Returns the model's ID;.
double getAccelerationLat() const
return the lateral speed of the current lane change maneuver
void setOrigLeaderGaps(CLeaderDist, double secGap)
virtual int wantsChangeSublane(int laneOffset, LaneChangeAction alternatives, const MSLeaderDistanceInfo &leaders, const MSLeaderDistanceInfo &followers, const MSLeaderDistanceInfo &blockers, const MSLeaderDistanceInfo &neighLeaders, const MSLeaderDistanceInfo &neighFollowers, const MSLeaderDistanceInfo &neighBlockers, const MSLane &neighLane, const std::vector< MSVehicle::LaneQ > &preb, MSVehicle **lastBlocked, MSVehicle **firstBlocked, double &latDist, double &targetDistLat, int &blocked)
void setManeuverDist(const double dist)
Updates the remaining distance for the current maneuver while it is continued within non-action steps...
std::vector< std::pair< double, bool > > myLCAccelerationAdvices
void setShadowApproachingInformation(MSLink *link) const
set approach information for the shadow vehicle
const std::vector< MSLane * > & getFurtherTargetLanes() const
int getNormalizedLaneIndex()
brief return lane index that treats opposite lanes like normal lanes to the left of the forward lanes
virtual int checkChangeBeforeCommitting(const MSVehicle *veh, int state) const
Informs the vehicle that it is about to be moved on an adjacent lane. The method can be used to re-ev...
virtual double patchSpeed(const double min, const double wanted, const double max, const MSCFModel &cfModel)=0
Called to adapt the speed in order to allow a lane change. It uses information on LC-related desired ...
static MSAbstractLaneChangeModel * build(LaneChangeModel lcm, MSVehicle &vehicle)
Factory method for instantiating new lane changing models.
void changedToOpposite()
called when a vehicle changes between lanes in opposite directions
void setSpeedLat(double speedLat)
set the lateral speed and update lateral acceleraton
MSLane * myTargetLane
The target lane for the vehicle's current maneuver.
MSLane * determineTargetLane(int &targetDir) const
double myPreviousManeuverDist
Maneuver distance from the previous simulation step.
double getMaxSpeedLat2() const
return the max of maxSpeedLat and lcMaxSpeedLatStanding
std::vector< double > myShadowFurtherLanesPosLat
MSLane * myShadowLane
A lane that is partially occupied by the front of the vehicle but that is not the primary lane.
double mySpeedLat
the current lateral speed
virtual void updateSafeLatDist(const double travelledLatDist)
Updates the value of safe lateral distances (in SL2015) during maneuver continuation in non-action st...
void checkTraCICommands()
Check for commands issued for the vehicle via TraCI and apply the appropriate state changes For the s...
double myManeuverDist
The complete lateral distance the vehicle wants to travel to finish its maneuver Only used by sublane...
int myLaneChangeDirection
direction of the lane change maneuver -1 means right, 1 means left
void primaryLaneChanged(MSLane *source, MSLane *target, int direction)
called once when the vehicles primary lane changes
int getShadowDirection() const
return the direction in which the current shadow lane lies
double myLastLeaderSpeed
speeds of surrounding vehicles at the time of lane change
virtual void loadState(const SUMOSAXAttributes &attrs)
Loads the state of the laneChangeModel from the given attributes.
MSAbstractLaneChangeModel(MSVehicle &v, const LaneChangeModel model)
Constructor.
MSVehicle & myVehicle
The vehicle this lane-changer belongs to.
virtual void setParameter(const std::string &key, const std::string &value)
try to set the given parameter for this laneChangeModel. Throw exception for unsupported key
double calcAngleOffset()
return the angle offset during a continuous change maneuver
void setPreviousAngleOffset(const double angleOffset)
set the angle offset of the previous time step
double myAngleOffset
the current angle offset resulting from lane change and sigma
double myLastLateralGapLeft
the minimum lateral gaps to other vehicles that were found when last changing to the left and right
double getSpeedLat() const
return the lateral speed of the current lane change maneuver
MSLane * getTargetLane() const
Returns the lane the vehicle has committed to enter during a sublane lane change.
virtual ~MSAbstractLaneChangeModel()
Destructor.
static void initGlobalOptions(const OptionsCont &oc)
init global model parameters
virtual bool sublaneChangeCompleted(const double latDist) const
whether the current change completes the manoeuvre
bool alreadyChanged() const
reset the flag whether a vehicle already moved to false
virtual StateAndDist decideDirection(StateAndDist sd1, StateAndDist sd2) const
decide in which direction to move in case both directions are desirable
double getAngleOffset() const
return the angle offset resulting from lane change and sigma
void memorizeGapsAtLCInit()
Control for resetting the memorized values for LC relevant gaps until the LC output is triggered in t...
static bool outputLCStarted()
whether start of maneuvers shall be recorede
double myLaneChangeCompletion
progress of the lane change maneuver 0:started, 1:complete
virtual bool debugVehicle() const
whether the current vehicles shall be debugged
virtual void changed()=0
bool isChangingLanes() const
return true if the vehicle currently performs a lane change maneuver
std::vector< MSLane * > myShadowFurtherLanes
virtual bool congested(const MSVehicle *const neighLeader)
void clearNeighbors()
Clear info on neighboring vehicle from previous step.
void saveNeighbors(const int dir, const MSLeaderDistanceInfo &followers, const MSLeaderDistanceInfo &leaders)
Saves the lane change relevant vehicles, which are currently on neighboring lanes in the given direct...
const MSVehicleType & getVehicleType() const
Returns the vehicle's type definition.
The car-following model abstraction.
Definition: MSCFModel.h:55
Representation of a lane in the micro simulation.
Definition: MSLane.h:84
saves leader/follower vehicles and their distances relative to an ego vehicle
Definition: MSLeaderInfo.h:144
Notification
Definition of a vehicle state.
@ NOTIFICATION_LANE_CHANGE
The vehicle changes lanes (micro only)
Representation of a vehicle in the micro simulation.
Definition: MSVehicle.h:77
MSAbstractLaneChangeModel & getLaneChangeModel()
Definition: MSVehicle.cpp:5774
const MSCFModel & getCarFollowModel() const
Returns the vehicle's car following model definition.
Definition: MSVehicle.h:977
const LatAlignmentDefinition & getPreferredLateralAlignment() const
Get vehicle's preferred lateral alignment procedure.
A storage for options typed value containers)
Definition: OptionsCont.h:89
Static storage of an output device and its base (abstract) implementation.
Definition: OutputDevice.h:61
Encapsulated SAX-Attributes.
StateAndDist(int _state, double _latDist, double _targetDist, int _dir)
bool sameDirection(const StateAndDist &other) const