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-2023 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  * Daniel Heß - initial API and implementation
13  ********************************************************************************/
14 
15 #pragma once
16 
19 #include <adore/fun/missiondata.h>
29 #include <adore/mad/com_patterns.h>
31 
32 namespace adore
33 {
34  namespace fun
35  {
39  class AFactory
40  {
41  public:
70 
71 
72  public:
137  //read lanechange suppression msgs
139  //read force lanechange left msgs
141  //read force lanechange right msgs
143  //read force slow maneuvers msgs
145  };
146 
147 
153  class FunFactoryInstance final
154  {
155  private:
157 
164  {
165  static FunFactoryInstance instance;
166  return instance;
167  }
168 
169  public:
171  {
172  if (getInstance().funFactory_ == 0)
173  {
174  std::cerr << " WARNING Accessing singleton funFactory instance without ever running init()"
175  << std::endl;
176  }
177  return getInstance().funFactory_;
178  }
179 
188  static void init(adore::fun::AFactory* funFactory)
189  {
190  auto& instance = getInstance();
191  instance.funFactory_ = funFactory;
192  }
193 
194  private:
195  FunFactoryInstance() = default;
196  ~FunFactoryInstance() = default;
197 
202  };
203 
204  } // namespace fun
205 } // namespace adore
abstract factory for adore::env communication
Definition: afactory.h:41
adore::mad::AWriter< MotionCommand > TMotionCommandWriter
Definition: afactory.h:49
adore::mad::AWriter< IndicatorCommand > TIndicatorCommandWriter
Definition: afactory.h:53
adore::mad::AReader< IndicatorCommand > TIndicatorCommandReader
Definition: afactory.h:54
virtual TMissionDataWriter * getMissionDataWriter()=0
write mission data
virtual TSetPointRequestWriter * getSetPointRequestWriter()=0
write updates on the setpoint request
virtual TPlanningResultFeed * getPlanningSelectFeed()=0
reads selected PlanningResult as general information about decision-making and planning performance
adore::mad::AReader< NavigationGoal > TNavigationGoalReader
Definition: afactory.h:42
virtual TPlanningRequestWriter * getPlanningRequestWriter()=0
writes PlanningRequest to orchestrate multiple trajectory planners
adore::mad::AReader< bool > TForceLanechangeRightReader
Definition: afactory.h:68
virtual TVehicleExtendedStateReader * getVehicleExtendedStateReader()=0
get updates on the vehicle extended state (buttons, etc.)
adore::mad::AFeed< PlanningResult > TPlanningResultFeed
Definition: afactory.h:59
virtual TMotionStateFeed * getVehicleLocalizationMotionStateFeed()=0
get updates on the vehicle motion state: best estimate from localization module
virtual TSetPointRequestWriter * getOdomSetPointRequestWriter()=0
write updates on the odom setpoint request: this is used by planner, if controller is operating in od...
virtual TGearSelectionCommandReader * getGearSelectionCommandReader()=0
read a gear selection command
virtual TTerminalRequestReader * getTerminalRequestReader()=0
get updates on the terminal request
adore::mad::AWriter< TerminalRequest > TTerminalRequestWriter
Definition: afactory.h:48
virtual TIndicatorCommandWriter * getIndicatorCommandWriter()=0
write an indicator command
virtual TPlatooningStateReader * getPlatooningStateReader()=0
get updates on the platooning state
adore::mad::AReader< MotionCommand > TMotionCommandReader
Definition: afactory.h:50
virtual TTerminalRequestWriter * getTerminalRequestWriter()=0
write updates on the terminal request
adore::mad::AReader< PlatooningInformation > TPlatooningStateReader
Definition: afactory.h:64
adore::mad::AReader< GearSelectionCommand > TGearSelectionCommandReader
Definition: afactory.h:52
adore::mad::AWriter< VehicleExtendedState > TVehicleExtendedStateWriter
Definition: afactory.h:56
adore::mad::AReader< bool > TLanechangeSuppressionReader
Definition: afactory.h:66
adore::mad::AWriter< PlanningRequest > TPlanningRequestWriter
Definition: afactory.h:60
adore::mad::AReader< MissionData > TMissionDataReader
Definition: afactory.h:63
virtual TIndicatorCommandReader * getIndicatorCommandReader()=0
read an indicator command
adore::mad::AReader< SetPointRequest > TSetPointRequestReader
Definition: afactory.h:43
virtual TMotionStateReader * getVehicleMotionStateReader()=0
get updates on the vehicle motion state: best estimate from localization module
adore::mad::AFeedWithCallback< PlanningRequest > TPlanningRequestTrigger
Definition: afactory.h:61
adore::mad::AWriter< MissionData > TMissionDataWriter
Definition: afactory.h:62
virtual TForceSlowManeuversReader * getForceSlowManeuversReader()=0
virtual TSetPointRequestReader * getSetPointRequestReader()=0
get updates on the setpoint request
virtual TNavigationGoalReader * getNavigationGoalReader()=0
get updates on the navigation goal
adore::mad::AWriter< GearSelectionCommand > TGearSelectionCommandWriter
Definition: afactory.h:51
adore::mad::AReader< bool > TForceLanechangeLeftReader
Definition: afactory.h:67
virtual TMotionStateReader * getVehicleOdometryMotionStateReader()=0
get updates on the vehicle motion state: best estimate from odometry module
virtual TMotionCommandReader * getMotionCommandReader()=0
read a motion command
virtual TMotionCommandWriter * getMotionCommandWriter()=0
write a motion command
adore::mad::AReader< VehicleExtendedState > TVehicleExtendedStateReader
Definition: afactory.h:55
adore::mad::AWriter< VehicleBaseMeasurement > TVehicleBaseMeasurementWriter
Definition: afactory.h:57
adore::mad::AReader< VehicleMotionState9d > TMotionStateReader
Definition: afactory.h:45
virtual TSetPointRequestReader * getOdomSetPointRequestReader()=0
get updates on the odom setpoint request: this is used by tracking controller, if controller is opera...
virtual TPlanningResultFeed * getPlanningResultFeed()=0
reads PlanningResult as general information about decision making and planning performance
virtual TVehicleBaseMeasurementWriter * getVehicleBaseMeasurementWriter()=0
writes measurements of base vehicle system into automation system
virtual TMissionDataReader * getMissionDataReader()=0
read mission data
virtual TSetPointRequestWriter * getNominalTrajectoryWriter()=0
write updates on the nominal trajectory
virtual TForceLanechangeLeftReader * getForceLanechangeLeftReader()=0
virtual TForceLanechangeRightReader * getForceLanechangeRightReader()=0
adore::mad::AFeed< VehicleMotionState9d > TMotionStateFeed
Definition: afactory.h:46
virtual TVehicleExtendedStateWriter * getVehicleExtendedStateWriter()=0
write updates on the vehicle extended state (buttons, etc.)
virtual TGearSelectionCommandWriter * getGearSelectionCommandWriter()=0
write a gear selection command
virtual TPlatooningStateWriter * getPlatooningStateWriter()=0
write updates on the platooning state
adore::mad::AWriter< PlatooningInformation > TPlatooningStateWriter
Definition: afactory.h:65
virtual TLanechangeSuppressionReader * getLanechangeSuppressionReader()=0
adore::mad::AReader< bool > TForceSlowManeuversReader
Definition: afactory.h:69
adore::mad::AWriter< PlanningResult > TPlanningResultWriter
Definition: afactory.h:58
virtual TMotionStateFeed * getVehicleOdometryMotionStateFeed()=0
get updates on the vehicle motion state: best estimate from odometry module
virtual TPlanningRequestTrigger * getPlanningRequestTrigger()=0
allows to trigger planning, when planning request is received
virtual TPlanningResultWriter * getPlanningSelectWriter()=0
writes PlanningResult for maneuver selected for execution
virtual TPlanningResultWriter * getPlanningResultWriter()=0
writes PlanningResult as general information about decision making and planning performance
adore::mad::AReader< TerminalRequest > TTerminalRequestReader
Definition: afactory.h:47
adore::mad::AWriter< SetPointRequest > TSetPointRequestWriter
Definition: afactory.h:44
virtual TSetPointRequestReader * getNominalTrajectoryReader()=0
get updates on the nominal trajectory
Utility class to simplify factory access.
Definition: afactory.h:154
static FunFactoryInstance & getInstance()
Function to access singleton instance of the funFactory using magic static.
Definition: afactory.h:163
FunFactoryInstance & operator=(FunFactoryInstance &&)=delete
static void init(adore::fun::AFactory *funFactory)
Initialize private members of funFactory.
Definition: afactory.h:188
static adore::fun::AFactory * get()
Definition: afactory.h:170
FunFactoryInstance(FunFactoryInstance &&)=delete
FunFactoryInstance(const FunFactoryInstance &)=delete
adore::fun::AFactory * funFactory_
Definition: afactory.h:156
FunFactoryInstance & operator=(const FunFactoryInstance &)=delete
Definition: com_patterns.h:46
Definition: com_patterns.h:29
Definition: com_patterns.h:68
Definition: com_patterns.h:97
Definition: areaofeffectconverter.h:20