Drake
drake::automotive Namespace Reference

Classes

class  AutomotiveSimulator
 AutomotiveSimulator is a helper class for constructing and running automotive-related simulations. More...
 
class  BicycleCar
 BicycleCar implements a nonlinear rigid body bicycle model from Althoff & Dolan (2014) [1]. More...
 
class  BicycleCarParameters
 Specializes BasicVector with specific getters and setters. More...
 
struct  BicycleCarParametersIndices
 Describes the row indices of a BicycleCarParameters. More...
 
class  BicycleCarParametersTranslator
 Translates between LCM message objects and VectorBase objects for the BicycleCarParameters type. More...
 
class  BicycleCarState
 Specializes BasicVector with specific getters and setters. More...
 
struct  BicycleCarStateIndices
 Describes the row indices of a BicycleCarState. More...
 
class  BicycleCarStateTranslator
 Translates between LCM message objects and VectorBase objects for the BicycleCarState type. More...
 
class  BoxCarVis
 BoxCarVis displays a box as the visual representation of a vehicle. More...
 
class  CarVis
 CarVis is a base class that provides visualization geometries and their poses. More...
 
class  CarVisApplicator
 CarVisApplicator takes as input a PoseVector containing vehicle poses. More...
 
struct  ClosestPose
 ClosestPose bundles together the RoadOdometry of a particular target along with its distance measure relative to the ego vehicle. More...
 
class  Curve2
 Curve2 represents a path through two-dimensional Cartesian space. More...
 
class  DrivingCommand
 Specializes BasicVector with specific getters and setters. More...
 
struct  DrivingCommandIndices
 Describes the row indices of a DrivingCommand. More...
 
class  DrivingCommandTranslator
 Translates between LCM message objects and VectorBase objects for the DrivingCommand type. More...
 
class  IdmController
 IdmController implements the IDM (Intelligent Driver Model) planner, computed based only on the nearest car ahead. More...
 
class  IdmPlanner
 IdmPlanner implements the IDM (Intelligent Driver Model) equation governing longitudinal accelerations of a vehicle in single-lane traffic [1, 2]. More...
 
class  IdmPlannerParameters
 Specializes BasicVector with specific getters and setters. More...
 
struct  IdmPlannerParametersIndices
 Describes the row indices of a IdmPlannerParameters. More...
 
struct  LaneDirection
 LaneDirection holds the lane that a MaliputRailcar is traversing and the direction in which it is moving. More...
 
class  MaliputRailcar
 MaliputRailcar models a vehicle that follows a maliput::api::Lane as if it were on rails and neglecting all physics. More...
 
class  MaliputRailcarParams
 Specializes BasicVector with specific getters and setters. More...
 
struct  MaliputRailcarParamsIndices
 Describes the row indices of a MaliputRailcarParams. More...
 
class  MaliputRailcarParamsTranslator
 Translates between LCM message objects and VectorBase objects for the MaliputRailcarParams type. More...
 
class  MaliputRailcarState
 Specializes BasicVector with specific getters and setters. More...
 
struct  MaliputRailcarStateIndices
 Describes the row indices of a MaliputRailcarState. More...
 
class  MaliputRailcarStateTranslator
 Translates between LCM message objects and VectorBase objects for the MaliputRailcarState type. More...
 
class  MobilPlanner
 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. More...
 
class  MobilPlannerParameters
 Specializes BasicVector with specific getters and setters. More...
 
struct  MobilPlannerParametersIndices
 Describes the row indices of a MobilPlannerParameters. More...
 
class  MonolaneOnrampMerge
 MonolaneOnrampMerge contains an example lane-merge scenario expressed as a maliput monolane road geometry. More...
 
class  PoseSelector
 PoseSelector is a class that provides the relevant pose or poses with respect to a given ego vehicle driving within a given maliput road geometry. More...
 
class  PriusVis
 PriusVis displays a visualization of a 2015 Toyota Prius. More...
 
class  PurePursuit
 PurePursuit computes the required steering angle to achieve a goal point on an continuous planar path. More...
 
class  PurePursuitController
 PurePursuitController implements a pure pursuit controller. More...
 
class  PurePursuitParams
 Specializes BasicVector with specific getters and setters. More...
 
struct  PurePursuitParamsIndices
 Describes the row indices of a PurePursuitParams. More...
 
struct  RoadCharacteristics
 RoadCharacteristics computes and stores characteristics of a road network; i.e. More...
 
struct  RoadOdometry
 RoadOdometry contains the position of the vehicle with respect to a lane in a road, along with its velocity vector in the world frame. More...
 
class  RoadPath
 RoadPath converts a sequence of Maliput Lanes into a PiecewisePolynomial for the purpose of generating a path for a car to follow. More...
 
class  SimpleCar
 SimpleCar models an idealized response to driving commands, neglecting all physics. More...
 
class  SimpleCarParams
 Specializes BasicVector with specific getters and setters. More...
 
struct  SimpleCarParamsIndices
 Describes the row indices of a SimpleCarParams. More...
 
class  SimpleCarParamsTranslator
 Translates between LCM message objects and VectorBase objects for the SimpleCarParams type. More...
 
class  SimpleCarState
 Specializes BasicVector with specific getters and setters. More...
 
struct  SimpleCarStateIndices
 Describes the row indices of a SimpleCarState. More...
 
class  SimpleCarStateTranslator
 Translates between LCM message objects and VectorBase objects for the SimpleCarState type. More...
 
class  SimplePowertrain
 SimplePowertrain models a powertrain with first-order lag. More...
 
class  TrajectoryCar
 TrajectoryCar models a car that follows a pre-established trajectory. More...
 
class  TrajectoryCarParams
 Specializes BasicVector with specific getters and setters. More...
 
struct  TrajectoryCarParamsIndices
 Describes the row indices of a TrajectoryCarParams. More...
 
class  TrajectoryCarState
 Specializes BasicVector with specific getters and setters. More...
 
struct  TrajectoryCarStateIndices
 Describes the row indices of a TrajectoryCarState. More...
 
class  TrajectoryCarStateTranslator
 Translates between LCM message objects and VectorBase objects for the TrajectoryCarState type. More...
 

Enumerations

enum  AheadOrBehind { kAhead = 0, kBehind = 1 }
 Specifies whether to assess the cars ahead or behind the ego car at its current orientation with respect to its lane. More...
 

Functions

template<typename T >
calc_smooth_acceleration (const T &desired_acceleration, const T &max_velocity, const T &velocity_limit_kp, const T &current_velocity)
 Computes and returns an acceleration command that results in a smooth acceleration profile. More...
 
template double calc_smooth_acceleration< double > (const double &desired_acceleration, const double &current_velocity, const double &max_velocity, const double &velocity_limit_kp)
 
template AutoDiffXd calc_smooth_acceleration< AutoDiffXd > (const AutoDiffXd &desired_acceleration, const AutoDiffXd &current_velocity, const AutoDiffXd &max_velocity, const AutoDiffXd &velocity_limit_kp)
 
template Expression calc_smooth_acceleration< Expression > (const Expression &desired_acceleration, const Expression &current_velocity, const Expression &max_velocity, const Expression &velocity_limit_kp)
 
std::unique_ptr< systems::Diagram< double > > CreateCarSimLcmDiagram (const DrivingCommandTranslator &driving_command_translator, std::unique_ptr< RigidBodyTree< double >> tree, lcm::DrakeLcmInterface *lcm)
 
std::tuple< Curve2< double >, double, doubleCreateTrajectoryParams (int index)
 Creates TrajectoryCar constructor demo arguments. More...
 
std::tuple< Curve2< double >, double, doubleCreateTrajectoryParamsForDragway (const maliput::dragway::RoadGeometry &road_geometry, int index, double speed, double start_time)
 Creates TrajectoryCar constructor demo arguments for a vehicle on a dragway. More...
 

Variables

static constexpr int kIdmParamsIndex {0}
 
static constexpr int kPpParamsIndex {0}
 
static constexpr int kCarParamsIndex {1}
 

Enumeration Type Documentation

enum AheadOrBehind
strong

Specifies whether to assess the cars ahead or behind the ego car at its current orientation with respect to its lane.

Enumerator
kAhead 
kBehind 

Function Documentation

T calc_smooth_acceleration ( const T &  desired_acceleration,
const T &  max_velocity,
const T &  velocity_limit_kp,
const T &  current_velocity 
)

Computes and returns an acceleration command that results in a smooth acceleration profile.

It is smooth in the sense that it looks pleasant and realistic, though it may not reflect the actual acceleration behavior of real vehicles.

For a given acceleration plan, all of the input parameters typically remain constant except for current_velocity.

Instantiated templates for the following ScalarTypes are provided:

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

Here is the call graph for this function:

Here is the caller graph for this function:

template AutoDiffXd drake::automotive::calc_smooth_acceleration< AutoDiffXd > ( const AutoDiffXd desired_acceleration,
const AutoDiffXd current_velocity,
const AutoDiffXd max_velocity,
const AutoDiffXd velocity_limit_kp 
)

Here is the caller graph for this function:

template double drake::automotive::calc_smooth_acceleration< double > ( const double desired_acceleration,
const double current_velocity,
const double max_velocity,
const double velocity_limit_kp 
)

Here is the caller graph for this function:

template Expression drake::automotive::calc_smooth_acceleration< Expression > ( const Expression &  desired_acceleration,
const Expression &  current_velocity,
const Expression &  max_velocity,
const Expression &  velocity_limit_kp 
)

Here is the caller graph for this function:

std::unique_ptr< systems::Diagram< double > > CreateCarSimLcmDiagram ( const DrivingCommandTranslator driving_command_translator,
std::unique_ptr< RigidBodyTree< double >>  tree,
lcm::DrakeLcmInterface lcm 
)
std::tuple< Curve2< double >, double, double > CreateTrajectoryParams ( int  index)

Creates TrajectoryCar constructor demo arguments.

The details of the trajectory are not documented / promised by this API.

Parameters
indexSelects which pre-programmed trajectory to use.
Returns
tuple of curve, speed, start_time
std::tuple< Curve2< double >, double, double > CreateTrajectoryParamsForDragway ( const maliput::dragway::RoadGeometry road_geometry,
int  index,
double  speed,
double  start_time 
)

Creates TrajectoryCar constructor demo arguments for a vehicle on a dragway.

The details of the trajectory are not documented / promised by this API.

Parameters
road_geometryThe dragway upon which the TrajectoryCar will travel.
indexThe lane index within the provided road_geometry.
speedThe speed of the vehicle.
start_timeThe time when the vehicle should start driving.
Returns
tuple of curve, speed, start_time

Here is the call graph for this function:

Variable Documentation

constexpr int kCarParamsIndex {1}
static
constexpr int kIdmParamsIndex {0}
static
constexpr int kPpParamsIndex {0}
static