Drake
idm_planner.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "drake/automotive/gen/idm_planner_parameters.h"
5 
6 namespace drake {
7 namespace automotive {
8 
9 /// IdmPlanner implements the IDM (Intelligent Driver Model) equation governing
10 /// longitudinal accelerations of a vehicle in single-lane traffic [1, 2]. It
11 /// is derived based on qualitative observations of actual driving behavior and
12 /// captures objectives such as keeping a safe distance behind a lead vehicle,
13 /// maintaining a desired speed, and accelerating and decelerating within
14 /// comfortable limits.
15 ///
16 /// The IDM equation produces accelerations that realize smooth transitions
17 /// between the following three modes:
18 /// - Free-road behavior: when the distance to the leading car is large, the
19 /// IDM regulates acceleration to match the desired speed `v_0`.
20 /// - Fast-closing-speed behavior: when the target distance decreases, an
21 /// interaction term compensates for the velocity difference, while keeping
22 /// deceleration comfortable according to parameter `b`.
23 /// - Small-distance behavior: within small net distances to the lead vehicle,
24 /// comfort is ignored in favor of increasing this distance to `s_0`.
25 ///
26 /// See the corresponding .cc file for details about the IDM equation.
27 ///
28 /// Instantiated templates for the following kinds of T's are provided:
29 /// - double
30 /// - drake::AutoDiffXd
31 /// - drake::symbolic::Expression
32 ///
33 /// They are already available to link against in the containing library.
34 ///
35 /// [1] Martin Treiber and Arne Kesting. Traffic Flow Dynamics, Data, Models,
36 /// and Simulation. Springer, 2013.
37 ///
38 /// [2] https://en.wikipedia.org/wiki/Intelligent_driver_model.
39 template <typename T>
40 class IdmPlanner {
41  public:
43  IdmPlanner() = delete;
44 
45  /// Evaluates the IDM equation for the chosen planner parameters @p params,
46  /// given the current velocity @p ego_velocity, distance to the lead car @p
47  /// target_distance, and the closing velocity @p target_distance_dot. The
48  /// returned value is a longitudinal acceleration.
49  static const T Evaluate(const IdmPlannerParameters<T>& params,
50  const T& ego_velocity, const T& target_distance,
51  const T& target_distance_dot);
52 };
53 
54 } // namespace automotive
55 } // namespace drake
IdmPlanner implements the IDM (Intelligent Driver Model) equation governing longitudinal acceleration...
Definition: idm_planner.h:40
Definition: automotive_demo.cc:88
static const T Evaluate(const IdmPlannerParameters< T > &params, const T &ego_velocity, const T &target_distance, const T &target_distance_dot)
Evaluates the IDM equation for the chosen planner parameters params, given the current velocity ego_v...
Definition: idm_planner.cc:17
#define DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Classname)
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN deletes the special member functions for copy-construction, copy-assignment, move-construction, and move-assignment.
Definition: drake_copyable.h:33
Provides careful macros to selectively enable or disable the special member functions for copy-constr...