delphyne
IDMController< T > Class Template Reference

Detailed Description

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

IDMController implements the IDM (Intelligent Driver Model) planner, computed based only on the nearest car ahead.

See IdmPlanner and PoseSelector for details. The output of this block is an acceleration value passed as a command to the vehicle.

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: PoseVector for the ego car. (InputPort getter: ego_pose_input())

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

Input Port 2: PoseBundle for the traffic cars, possibly inclusive of the ego car's pose. (InputPort getter: traffic_input())

Output Port 0: A BasicVector containing the acceleration request. (OutputPort getter: acceleration_output())

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

  • double
  • AutoDiffXd

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

#include <src/systems/idm_controller.h>

Inheritance diagram for IDMController< T >:
[legend]

Public Member Functions

 IDMController (const maliput::api::RoadGeometry &road, ScanStrategy path_or_branches, RoadPositionStrategy road_position_strategy, double period_sec)
 Constructor. More...
 
template<typename U >
 IDMController (const IDMController< U > &other)
 Scalar-converting copy constructor. More...
 
 ~IDMController () override
 
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 > & traffic_input () const
 
const drake::systems::OutputPort< T > & acceleration_output () const
 

Protected Member Functions

const maliput::api::RoadGeometryroad () const
 
int ego_pose_index () const
 
int ego_velocity_index () const
 
int traffic_index () const
 
int acceleration_index () const
 
void ImplCalcAcceleration (const drake::systems::rendering::PoseVector< T > &ego_pose, const drake::systems::rendering::FrameVelocity< T > &ego_velocity, const drake::systems::rendering::PoseBundle< T > &traffic_poses, const IdmPlannerParameters< T > &idm_params, const maliput::api::RoadPosition &ego_rp, drake::systems::BasicVector< T > *command) const
 
void DoCalcUnrestrictedUpdate (const drake::systems::Context< T > &context, const std::vector< const drake::systems::UnrestrictedUpdateEvent< T > * > &, drake::systems::State< T > *state) const override
 

Friends

template<typename >
class IDMController
 

Constructor & Destructor Documentation

◆ IDMController() [1/2]

IDMController ( const maliput::api::RoadGeometry road,
ScanStrategy  path_or_branches,
RoadPositionStrategy  road_position_strategy,
double  period_sec 
)

Constructor.

Parameters
roadThe pre-defined RoadGeometry.
path_or_branchesIf ScanStrategy::kBranches, performs IDM computations using vehicles detected in confluent branches; if ScanStrategy::kPath, limits to vehicles on the default path. See documentation for PoseSelector::FindSingleClosestPose().
road_position_strategyDetermines whether or not to cache RoadPosition. See calc_ongoing_road_position.h.
period_secThe update period to use if road_position_strategy == RoadPositionStrategy::kCache.

◆ IDMController() [2/2]

IDMController ( const IDMController< U > &  other)
explicit

Scalar-converting copy constructor.

◆ ~IDMController()

~IDMController
override

Member Function Documentation

◆ acceleration_index()

int acceleration_index ( ) const
protected

◆ acceleration_output()

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

◆ 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_pose_index()

int ego_pose_index ( ) const
protected

◆ ego_pose_input()

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

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

◆ ego_velocity_index()

int ego_velocity_index ( ) const
protected

◆ ego_velocity_input()

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

◆ ImplCalcAcceleration()

void ImplCalcAcceleration ( const drake::systems::rendering::PoseVector< T > &  ego_pose,
const drake::systems::rendering::FrameVelocity< T > &  ego_velocity,
const drake::systems::rendering::PoseBundle< T > &  traffic_poses,
const IdmPlannerParameters< T > &  idm_params,
const maliput::api::RoadPosition ego_rp,
drake::systems::BasicVector< T > *  command 
) const
protected

◆ road()

const maliput::api::RoadGeometry& road ( ) const
protected

◆ traffic_index()

int traffic_index ( ) const
protected

◆ traffic_input()

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

Friends And Related Function Documentation

◆ IDMController

friend class IDMController
friend

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