delphyne
MobilPlanner< T > Class Template Reference

Detailed Description

template<typename T>
class delphyne::MobilPlanner< T >

MOBIL (Minimizing Overall Braking Induced by Lane Changes) [1] is a planner that minimizes braking requirement for the ego car while also minimizing (per a weighting factor) the braking requirements of any trailing cars within the ego car's immediate neighborhood.

The weighting factor encapsulates the politeness of the ego car to the surrounding traffic. Neighboring cars are defined as those cars immediately ahead and behind the ego, in the current lane and any adjacent lanes; these are determined from the PoseSelector logic applied to a multi-lane Maliput road.

The induced braking by the ego car and the car following immediately behind it is compared with the induced braking by the ego and its new follower if the ego were to move to any of the neighboring lanes. The choice that minimizes the induced braking - alternatively maximizes the ego car's "incentive" (the weighted sum of accelerations that the ego car and its neighbors gain by changing lanes) - is chosen as the new lane request. The request is expressed as a LaneDirection, that references a valid lane in the provided RoadGeometry and the direction of travel.

Assumptions: 1) The planner supports only symmetric lane change rules, without giving preference to lanes to the left or right. 2) The planner assumes all traffic behaves according to the Intelligent Driver Model (IDM). 3) All neighboring lanes are confluent (i.e. with_s points in the same direction).

Instantiated templates for the following kinds of T's are provided:

  • double

They are already available to link against in the containing library.

Input Port 0: A PoseVector for the ego car. (InputPort getter: ego_pose_input())

Input Port 1: A FrameVelocity for the ego car. (InputPort getter: ego_velocity_input())

Input Port 2: A BasicVector containing the ego car's commanded acceleration value intercepted from the vehicle's controller (e.g. IdmController). (InputPort getter: ego_acceleration_input())

Input Port 3: A PoseBundle for the traffic cars, possibly including the ego car's pose. (InputPort getter: traffic_input())

Output Port 0: A LaneDirection containing a lane that the ego vehicle must move into and the direction of travel with respect to the lane's canonical direction of travel. LaneDirection must be consistent with the provided road. (OutputPort getter: lane_output())

[1] Arne Kesting, Martin Treiber and Dirk Helbing, MOBIL: General Lane-Changing Model for Car-Following Models, Journal of the Transportation Research Board, v1999, 2007, pp 86-94. http://trrjournalonline.trb.org/doi/abs/10.3141/1999-10.

#include <src/systems/mobil_planner.h>

Inheritance diagram for MobilPlanner< T >:
[legend]

Public Types

typedef std::map< AheadOrBehind, const ClosestPose< T > > ClosestPoses
 

Public Member Functions

 MobilPlanner (const maliput::api::RoadGeometry &road, bool initial_with_s, RoadPositionStrategy road_position_strategy, double period_sec)
 A constructor that initializes the MOBIL planner. More...
 
const drake::systems::InputPort< T > & ego_pose_input () const
 See the class description for details on the following input ports. More...
 
const drake::systems::InputPort< T > & ego_velocity_input () const
 
const drake::systems::InputPort< T > & ego_acceleration_input () const
 
const drake::systems::InputPort< T > & traffic_input () const
 
const drake::systems::OutputPort< T > & lane_output () const
 
IdmPlannerParameters< T > & get_mutable_idm_params (drake::systems::Context< T > *context) const
 Getters to mutable named-vector references associated with MobilPlanner's Parameters groups. More...
 
MobilPlannerParameters< T > & get_mutable_mobil_params (drake::systems::Context< T > *context) const
 

Protected Member Functions

void DoCalcUnrestrictedUpdate (const drake::systems::Context< T > &context, const std::vector< const drake::systems::UnrestrictedUpdateEvent< T > * > &, drake::systems::State< T > *state) const override
 

Member Typedef Documentation

◆ ClosestPoses

typedef std::map<AheadOrBehind, const ClosestPose<T> > ClosestPoses

Constructor & Destructor Documentation

◆ MobilPlanner()

MobilPlanner ( const maliput::api::RoadGeometry road,
bool  initial_with_s,
RoadPositionStrategy  road_position_strategy,
double  period_sec 
)

A constructor that initializes the MOBIL planner.

Parameters
roadThe pre-defined RoadGeometry.
initial_with_sThe initial direction of travel in the lane corresponding to the ego vehicle's initial state.
road_position_strategyDetermines whether or not to memorize RoadPosition. See calc_ongoing_road_position.h.
period_secThe update period to use if road_position_strategy == RoadPositionStrategy::kCache.

Member Function Documentation

◆ DoCalcUnrestrictedUpdate()

void DoCalcUnrestrictedUpdate ( const drake::systems::Context< T > &  context,
const std::vector< const drake::systems::UnrestrictedUpdateEvent< T > * > &  ,
drake::systems::State< T > *  state 
) const
overrideprotected

◆ ego_acceleration_input()

const drake::systems::InputPort< T > & ego_acceleration_input

◆ ego_pose_input()

const drake::systems::InputPort< T > & ego_pose_input

See the class description for details on the following input ports.

◆ ego_velocity_input()

const drake::systems::InputPort< T > & ego_velocity_input

◆ get_mutable_idm_params()

IdmPlannerParameters<T>& get_mutable_idm_params ( drake::systems::Context< T > *  context) const

Getters to mutable named-vector references associated with MobilPlanner's Parameters groups.

◆ get_mutable_mobil_params()

MobilPlannerParameters<T>& get_mutable_mobil_params ( drake::systems::Context< T > *  context) const

◆ lane_output()

const drake::systems::OutputPort< T > & lane_output

◆ traffic_input()

const drake::systems::InputPort< T > & traffic_input

The documentation for this class was generated from the following files: