107 std::cerr <<
" WARNING Accessing singleton paramsFactory instance without ever running init()"
124 instance.paramsFactory_ = paramsFactory;
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
~ParamsFactoryInstance()=default
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
ParamsFactoryInstance()=default
Definition: areaofeffectconverter.h:20