Drake
AutomotiveSimulator< T > Class Template Reference

AutomotiveSimulator is a helper class for constructing and running automotive-related simulations. More...

#include <automotive/automotive_simulator.h>

Public Member Functions

 AutomotiveSimulator ()
 The default constructor that configures this object with a default- constructed DrakeLcm instance. More...
 
 AutomotiveSimulator (std::unique_ptr< lcm::DrakeLcmInterface > lcm)
 A constructor that configures this object to use a DrakeLcmInterface instance. More...
 
 ~AutomotiveSimulator ()
 
lcm::DrakeLcmInterfaceget_lcm ()
 Returns the LCM object used by this AutomotiveSimulator. More...
 
systems::DiagramBuilder< T > * get_builder ()
 Returns the DiagramBuilder. More...
 
int AddPriusSimpleCar (const std::string &name, const std::string &channel_name=std::string(), const SimpleCarState< T > &initial_state=SimpleCarState< T >())
 Adds a SimpleCar to this simulation visualized as a Toyota Prius. More...
 
int AddMobilControlledSimpleCar (const std::string &name, bool initial_with_s, ScanStrategy path_or_branches, RoadPositionStrategy road_position_strategy, double period_sec, const SimpleCarState< T > &initial_state=SimpleCarState< T >())
 Adds a SimpleCar to this simulation controlled by a MOBIL planner coupled with a PurePursuitController to perform lateral control of the vehicle, along with an IDM longitudinal controller. More...
 
int AddPriusTrajectoryCar (const std::string &name, const Curve2< double > &curve, double speed, double start_time)
 Adds a TrajectoryCar to this simulation visualized as a Toyota Prius. More...
 
int AddIdmControlledCar (const std::string &name, bool initial_with_s, const SimpleCarState< T > &initial_state, const maliput::api::Lane *goal_lane, ScanStrategy path_or_branches, RoadPositionStrategy road_position_strategy, double period_sec)
 Adds a lane-following SimpleCar with IdmController and PurePursuitController to this simulation that takes as input a constant source that contains the goal_lane as the destination lane for the car. More...
 
int AddPriusMaliputRailcar (const std::string &name, const LaneDirection &initial_lane_direction, const MaliputRailcarParams< T > &params=MaliputRailcarParams< T >(), const MaliputRailcarState< T > &initial_state=MaliputRailcarState< T >())
 Adds a MaliputRailcar to this simulation visualized as a Toyota Prius. More...
 
int AddIdmControlledPriusMaliputRailcar (const std::string &name, const LaneDirection &initial_lane_direction, ScanStrategy path_or_branches, RoadPositionStrategy road_position_strategy, double period_sec, const MaliputRailcarParams< T > &params=MaliputRailcarParams< T >(), const MaliputRailcarState< T > &initial_state=MaliputRailcarState< T >())
 Adds a MaliputRailcar to this simulation visualized as a Toyota Prius that is controlled via an IdmController. More...
 
void SetMaliputRailcarAccelerationCommand (int id, double acceleration)
 Sets the acceleration command of a particular MaliputRailcar. More...
 
const maliput::api::RoadGeometrySetRoadGeometry (std::unique_ptr< const maliput::api::RoadGeometry > road)
 Sets the RoadGeometry for this simulation. More...
 
const maliput::api::LaneFindLane (const std::string &name) const
 Finds and returns a pointer to a lane with the specified name. More...
 
systems::System< T > & GetBuilderSystemByName (std::string name)
 Returns the System whose name matches name. More...
 
const systems::System< T > & GetDiagramSystemByName (std::string name) const
 Returns the System whose name matches name. More...
 
void Build ()
 Builds the Diagram. More...
 
void BuildAndInitialize (std::unique_ptr< systems::Context< double >> initial_context=nullptr)
 Builds the Diagram and intializes the Diagram Context to the predefined initial states. More...
 
const systems::System< T > & GetDiagram () const
 Returns the System containing the entire AutomotiveSimulator diagram. More...
 
void Start (double target_realtime_rate=0.0, std::unique_ptr< systems::Context< double >> initial_context=nullptr)
 Calls BuildAndInitialize() on the diagram (if it has not been build already) and initializes the Simulator. More...
 
bool has_started () const
 Returns whether the automotive simulator has started. More...
 
void StepBy (const T &time_step)
 Advances simulated time by the given time_step increment in seconds. More...
 
systems::rendering::PoseBundle< T > GetCurrentPoses () const
 Returns the current poses of all vehicles in the simulation. More...
 
Does not allow copy, move, or assignment
 AutomotiveSimulator (const AutomotiveSimulator &)=delete
 
AutomotiveSimulatoroperator= (const AutomotiveSimulator &)=delete
 
 AutomotiveSimulator (AutomotiveSimulator &&)=delete
 
AutomotiveSimulatoroperator= (AutomotiveSimulator &&)=delete
 

Detailed Description

template<typename T>
class drake::automotive::AutomotiveSimulator< T >

AutomotiveSimulator is a helper class for constructing and running automotive-related simulations.

Template Parameters
Tmust be a valid Eigen ScalarType.

Instantiated templates for the following ScalarTypes are provided:

  • double

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

Constructor & Destructor Documentation

AutomotiveSimulator ( const AutomotiveSimulator< T > &  )
delete

The default constructor that configures this object with a default- constructed DrakeLcm instance.

AutomotiveSimulator ( std::unique_ptr< lcm::DrakeLcmInterface lcm)
explicit

A constructor that configures this object to use a DrakeLcmInterface instance.

If nullptr, no visualization is produced.

Here is the call graph for this function:

Member Function Documentation

int AddIdmControlledCar ( const std::string &  name,
bool  initial_with_s,
const SimpleCarState< T > &  initial_state,
const maliput::api::Lane goal_lane,
ScanStrategy  path_or_branches,
RoadPositionStrategy  road_position_strategy,
double  period_sec 
)

Adds a lane-following SimpleCar with IdmController and PurePursuitController to this simulation that takes as input a constant source that contains the goal_lane as the destination lane for the car.

The car is visualized as a Toyota Prius. This includes its EulerFloatingJoint output.

Precondition
Start() has NOT been called.
Parameters
nameThe car's name, which must be unique among all cars. Otherwise a std::runtime_error will be thrown.
initial_with_sInitial travel direction in the lane. True means that the car is initially oriented in the positive-s direction.
initial_stateThe SimpleCar's initial state.
goal_laneThe goal lane for the car. If goal_lane is nullptr or not a member of the road supplied via SetRoadGeometry(), a std::runtime_error will be thrown.
path_or_branchesIf ScanStrategy::kBranches, performs IDM computations using vehicles detected in confluent branches; if ScanStrategy::kPath, limits to vehicles on the default path.
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.
Returns
The ID of the car that was just added to the simulation.

Here is the call graph for this function:

int AddIdmControlledPriusMaliputRailcar ( const std::string &  name,
const LaneDirection initial_lane_direction,
ScanStrategy  path_or_branches,
RoadPositionStrategy  road_position_strategy,
double  period_sec,
const MaliputRailcarParams< T > &  params = MaliputRailcarParams<T>(),
const MaliputRailcarState< T > &  initial_state = MaliputRailcarState<T>() 
)

Adds a MaliputRailcar to this simulation visualized as a Toyota Prius that is controlled via an IdmController.

Precondition
Start() has NOT been called.
SetRoadGeometry() was called. Otherwise, a std::runtime_error will be thrown.
Parameters
nameThe car's name, which must be unique among all cars. Otherwise a std::runtime_error will be thrown.
initial_lane_directionThe MaliputRailcar's initial lane and direction on the lane. The lane in this parameter must be part of the maliput::api::RoadGeometry that is added via SetRoadGeometry(). Otherwise a std::runtime_error will be thrown.
path_or_branchesIf ScanStrategy::kBranches, performs IDM computations using vehicles detected in confluent branches; if ScanStrategy::kPath, limits to vehicles on the default path.
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.
paramsThe MaliputRailcar's parameters. This is an optional parameter. Defaults are used if this parameter is not provided.
initial_stateThe MaliputRailcar's initial state. This is an optional parameter. Defaults are used if this parameter is not provided.
Returns
The ID of the car that was just added to the simulation.

Here is the call graph for this function:

int AddMobilControlledSimpleCar ( const std::string &  name,
bool  initial_with_s,
ScanStrategy  path_or_branches,
RoadPositionStrategy  road_position_strategy,
double  period_sec,
const SimpleCarState< T > &  initial_state = SimpleCarState<T>() 
)

Adds a SimpleCar to this simulation controlled by a MOBIL planner coupled with a PurePursuitController to perform lateral control of the vehicle, along with an IDM longitudinal controller.

The car is visualized as a Toyota Prius.

Precondition
Start() has NOT been called.
SetRoadGeometry() was called. Otherwise, a std::runtime_error will be thrown.
Parameters
nameThe car's name, which must be unique among all cars. Otherwise a std::runtime_error will be thrown.
initial_with_sInitial travel direction in the lane. (See MobilPlanner documentation.)
path_or_branchesIf ScanStrategy::kBranches, performs IDM computations using vehicles detected in confluent branches; if ScanStrategy::kPath, limits to vehicles on the default path.
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.
initial_stateThe SimpleCar's initial state.
Returns
The ID of the car that was just added to the simulation.

Here is the call graph for this function:

int AddPriusMaliputRailcar ( const std::string &  name,
const LaneDirection initial_lane_direction,
const MaliputRailcarParams< T > &  params = MaliputRailcarParams<T>(),
const MaliputRailcarState< T > &  initial_state = MaliputRailcarState<T>() 
)

Adds a MaliputRailcar to this simulation visualized as a Toyota Prius.

Precondition
Start() has NOT been called.
SetRoadGeometry() was called. Otherwise, a std::runtime_error will be thrown.
Parameters
nameThe car's name, which must be unique among all cars. Otherwise a std::runtime_error will be thrown.
initial_lane_directionThe MaliputRailcar's initial lane and direction on the lane. The lane in this parameter must be part of the maliput::api::RoadGeometry that is added via SetRoadGeometry(). Otherwise a std::runtime_error will be thrown.
paramsThe MaliputRailcar's parameters. This is an optional parameter. Defaults are used if this parameter is not provided.
initial_stateThe MaliputRailcar's initial state. This is an optional parameter. Defaults are used if this parameter is not provided.
Returns
The ID of the car that was just added to the simulation.

Here is the call graph for this function:

Here is the caller graph for this function:

int AddPriusSimpleCar ( const std::string &  name,
const std::string &  channel_name = std::string(),
const SimpleCarState< T > &  initial_state = SimpleCarState<T>() 
)

Adds a SimpleCar to this simulation visualized as a Toyota Prius.

This includes its DrivingCommand LCM input.

Precondition
Start() has NOT been called.
Parameters
nameThe car's name, which must be unique among all cars. Otherwise a std::runtime_error will be thrown.
channel_nameThe SimpleCar will subscribe to an LCM channel of this name to receive commands. If empty, then the input port is fixed to a DrivingCommand created using its default constructor.
initial_stateThe SimpleCar's initial state.
Returns
The ID of the car that was just added to the simulation.

Here is the call graph for this function:

int AddPriusTrajectoryCar ( const std::string &  name,
const Curve2< double > &  curve,
double  speed,
double  start_time 
)

Adds a TrajectoryCar to this simulation visualized as a Toyota Prius.

Precondition
Start() has NOT been called.
Parameters
nameThe car's name, which must be unique among all cars. Otherwise a std::runtime_error will be thrown.
curveSee documentation of TrajectoryCar::TrajectoryCar.
speedSee documentation of TrajectoryCar::TrajectoryCar.
start_timeSee documentation of TrajectoryCar::TrajectoryCar.
Returns
The ID of the car that was just added to the simulation.

Here is the call graph for this function:

void Build ( )

Builds the Diagram.

No further changes to the diagram may occur after this has been called.

Precondition
Build() and BuildandInitialize() have NOT been called.

Here is the call graph for this function:

Here is the caller graph for this function:

void BuildAndInitialize ( std::unique_ptr< systems::Context< double >>  initial_context = nullptr)

Builds the Diagram and intializes the Diagram Context to the predefined initial states.

Precondition
Build() and BuildandInitialize() have NOT been called.

Here is the call graph for this function:

Here is the caller graph for this function:

const maliput::api::Lane * FindLane ( const std::string &  name) const

Finds and returns a pointer to a lane with the specified name.

This method throws a std::runtime_error if no such lane exists.

Precondition
SetRoadGeometry() was called.

Here is the call graph for this function:

Here is the caller graph for this function:

systems::DiagramBuilder< T > * get_builder ( )

Returns the DiagramBuilder.

Precondition
Start() has NOT been called.

Here is the call graph for this function:

lcm::DrakeLcmInterface * get_lcm ( )

Returns the LCM object used by this AutomotiveSimulator.

systems::System< T > & GetBuilderSystemByName ( std::string  name)

Returns the System whose name matches name.

Throws an exception if no such system has been added, or multiple such systems have been added. This is the builder variant of the method. It can only be used prior to Start() being called.

Precondition
Start() has NOT been called.

Here is the call graph for this function:

PoseBundle< T > GetCurrentPoses ( ) const

Returns the current poses of all vehicles in the simulation.

Precondition
Start() has been called.

Here is the call graph for this function:

Here is the caller graph for this function:

const systems::System<T>& GetDiagram ( ) const
inline

Returns the System containing the entire AutomotiveSimulator diagram.

Precondition
either Build() or BuildandInitialize() have been called.

Here is the call graph for this function:

const systems::System< T > & GetDiagramSystemByName ( std::string  name) const

Returns the System whose name matches name.

Throws an exception if no such system has been added, or multiple such systems have been added.

This is the diagram variant of the method, which can only be used after Start() is called.

Precondition
Start() has been called.

Here is the call graph for this function:

bool has_started ( ) const
inline

Returns whether the automotive simulator has started.

Here is the call graph for this function:

Here is the caller graph for this function:

AutomotiveSimulator& operator= ( AutomotiveSimulator< T > &&  )
delete
AutomotiveSimulator& operator= ( const AutomotiveSimulator< T > &  )
delete
void SetMaliputRailcarAccelerationCommand ( int  id,
double  acceleration 
)

Sets the acceleration command of a particular MaliputRailcar.

Parameters
idThe ID of the MaliputRailcar. This is the ID that was returned by the method that added the MaliputRailcar to the simulation. If no MaliputRailcar with such an ID exists, a std::runtime_error is thrown.
accelerationThe acceleration command to issue to the MaliputRailcar.
Precondition
Start() has been called.

Here is the call graph for this function:

const RoadGeometry * SetRoadGeometry ( std::unique_ptr< const maliput::api::RoadGeometry road)

Sets the RoadGeometry for this simulation.

Precondition
Start() has NOT been called.

Here is the call graph for this function:

void Start ( double  target_realtime_rate = 0.0,
std::unique_ptr< systems::Context< double >>  initial_context = nullptr 
)

Calls BuildAndInitialize() on the diagram (if it has not been build already) and initializes the Simulator.

No further changes to the diagram may occur after this has been called.

Precondition
Start() has NOT been called.
Parameters
target_realtime_rateThis value is passed to systems::Simulator::set_target_realtime_rate().

Here is the call graph for this function:

Here is the caller graph for this function:

void StepBy ( const T &  time_step)

Advances simulated time by the given time_step increment in seconds.

Here is the call graph for this function:

Here is the caller graph for this function:


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