ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
afactory.h
Go to the documentation of this file.
1 /********************************************************************************
2  * Copyright (C) 2017-2020 German Aerospace Center (DLR).
3  * Eclipse ADORe, Automated Driving Open Research https://eclipse.org/adore
4  *
5  * This program and the accompanying materials are made available under the
6  * terms of the Eclipse Public License 2.0 which is available at
7  * http://www.eclipse.org/legal/epl-2.0.
8  *
9  * SPDX-License-Identifier: EPL-2.0
10  *
11  * Contributors:
12  * Jan Lauermann - initial API and implementation
13  ********************************************************************************/
14 
15 #pragma once
16 
38 #include <iostream>
39 
40 namespace adore
41 {
46  namespace params
47  {
48 
53  class AFactory
54  {
55 
56  public:
57  virtual APVehicle* getVehicle()const =0;
61  virtual APMapProvider* getMapProvider()const =0;
63  virtual APNavigation* getNavigation()const =0;
64  virtual APCooperation* getCooperation()const =0;
67  virtual APLaneChangeView* getLaneChangeView()const =0;
69  virtual APLocalRoadMap* getLocalRoadMap() const =0;
71  virtual APLateralPlanner* getLateralPlanner() const =0;
72  virtual APSensorModel* getSensorModel() const =0;
73  virtual APCheckpoints* getCheckpoints() const =0;
74  virtual APMissionControl* getMissionControl() const =0;
75  virtual APPrediction* getPrediction() const=0;
76  virtual APOdometryModel* getOdometryModel() const=0;
78 
79  };
80 
87  {
88  private:
90 
97  {
98  static ParamsFactoryInstance instance;
99  return instance;
100  }
101 
102  public:
104  {
105  if (getInstance().paramsFactory_ == 0)
106  {
107  std::cerr << " WARNING Accessing singleton paramsFactory instance without ever running init()"
108  << std::endl;
109  }
110  return getInstance().paramsFactory_;
111  }
112 
121  static void init(adore::params::AFactory* paramsFactory)
122  {
123  auto& instance = getInstance();
124  instance.paramsFactory_ = paramsFactory;
125  }
126 
127  private:
130 
135  };
136  }
137 }
abstract factory for adore::params classes
Definition: afactory.h:54
virtual APLocalRoadMap * getLocalRoadMap() const =0
virtual APLateralPlanner * getLateralPlanner() const =0
virtual APTacticalPlanner * getTacticalPlanner() const =0
virtual APTrajectoryTracking * getTrajectoryTracking() const =0
virtual APLocalizationModel * getLocalizationModel() const =0
virtual APTrajectoryGeneration * getTrajectoryGeneration() const =0
virtual APLaneFollowingView * getLaneFollowingView() const =0
virtual APNavigation * getNavigation() const =0
virtual APTrafficLightSim * getTrafficLightSim() const =0
virtual APVehicle * getVehicle() const =0
virtual APSensorModel * getSensorModel() const =0
virtual APPrediction * getPrediction() const =0
virtual APEmergencyOperation * getEmergencyOperation() const =0
virtual APLaneChangeView * getLaneChangeView() const =0
virtual APOdometryModel * getOdometryModel() const =0
virtual APMapProvider * getMapProvider() const =0
virtual APLongitudinalPlanner * getLongitudinalPlanner() const =0
virtual APCheckpoints * getCheckpoints() const =0
virtual APMissionControl * getMissionControl() const =0
virtual APFunctionManagement * getFunctionmanagement() const =0
virtual APCooperation * getCooperation() const =0
abstract class containing parameters for checkpoint handling
Definition: ap_checkpoints.h:25
abstract class containing cooperative behaviour parameters
Definition: ap_cooperation.h:26
abstract class containing parameters concerning emergency operation behaviour
Definition: ap_emergency_operation.h:25
abstract class containing parameters for function management configuration
Definition: ap_function_management.h:25
abstract class containing parameters for a lane change view
Definition: ap_lane_change_view.h:25
abstract class containing parameters for a lane following view
Definition: ap_lane_following_view.h:25
abstract class containing parameters related to configuring the lateral planner
Definition: ap_lateral_planner.h:26
abstract class to configure the local view of the road map
Definition: ap_local_road_map.h:26
abstract class containing parameters which configure localization state estimation model
Definition: ap_localizationmodel.h:26
abstract class containing parameters related to configuring the longitudinal planner
Definition: ap_longitudinal_planner.h:26
abstract class containing parameters to configure aspects of the map provider
Definition: ap_map_provider.h:25
abstract class containing parameters for mission controller configuration
Definition: ap_mission_control.h:25
abstract class containing parameters which configure navigation behaviour
Definition: ap_navigation.h:25
abstract class containing parameters which configure odometry state estimation model
Definition: ap_odometrymodel.h:26
parameter interface for parameters related to prediction
Definition: ap_prediction.h:28
abstract class for vehicle sensor model parameters
Definition: ap_sensor_model.h:27
abstract classs containing parameters to configure aspects and constraints of the tactical planner
Definition: ap_tactical_planner.h:25
abstract class containing parameters to configure aspects of the map provider
Definition: ap_traffic_light_sim.h:27
abstract class containing parameters to configure the behaviour of trajectory generation
Definition: ap_trajectory_generation.h:26
abstract class containing parameters to configure the behaviour of the trajactory tracking controller
Definition: ap_trajectory_tracking.h:26
abstract class for vehicle configuration related paremeters
Definition: ap_vehicle.h:29
Utility class to simplify factory access.
Definition: afactory.h:87
ParamsFactoryInstance(ParamsFactoryInstance &&)=delete
ParamsFactoryInstance & operator=(const ParamsFactoryInstance &)=delete
ParamsFactoryInstance(const ParamsFactoryInstance &)=delete
static ParamsFactoryInstance & getInstance()
Function to access singleton instance of the AllFactory using magic static.
Definition: afactory.h:96
ParamsFactoryInstance & operator=(ParamsFactoryInstance &&)=delete
static void init(adore::params::AFactory *paramsFactory)
Initialize private members of AllFactory.
Definition: afactory.h:121
adore::params::AFactory * paramsFactory_
Definition: afactory.h:89
static adore::params::AFactory * get()
Definition: afactory.h:103
Definition: areaofeffectconverter.h:20