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  * Daniel Heß - initial implementation and API
13  * Robert Markowski - extension of API
14  ********************************************************************************/
15 
16 #pragma once
17 
22 #include <adore/mad/com_patterns.h>
34 
35 namespace adore
36 {
37  namespace env
38  {
40  class AFactory
41  {
42  public:
75 
76  // write border
78  // read borders
79  virtual TBorderFeed* getBorderFeed()=0;
80 
81  // write Border Type Changes in road profile
84 
85  // env vehicle state -> odemetry msg
86  // vehicle state 9d in adore::env (um Link gegen FUN zu vermeiden)
87  // füllen mit Daten aus Odometry so weit wie möglich
89 
90  // read a set of traffic participants - provides the current, complete set of tracked objects
92 
93  // read navigation goal
95 
96  // write navigation data
98 
99  // read navigation data
101 
102  // write precedence rules
104 
105  // read precedence rules
107 
108  // write propositional logic information
110 
111  // read propositional logic information
113 
114  // read traffic light information: controlled connection specifies state of a connection, which is controlled by for example a traffic light
116 
117  // read checkpoint information represented as controlled connections
119 
120  //write checkpoint information represented as controlled connections
122 
123  // read the latest prediction set for expected behavior
125 
126  // read the latest prediction set for worst-case behavior
128 
129  // read the latest prediction set for expected behavior, unfiltered
131 
132  // read the latest prediction set for worst-case behavior, unfiltered
134 
135  // read the latest prediction set for desired behavior
137 
138  // read the latest prediction set for static obstacles
140 
141  // write the latest prediction set for expected behavior
143 
144  // write the latest prediction set for worst-case behavior
146 
147  // write the latest prediction set for expected behavior, unfiltered
149 
150  // write the latest prediction set for worst-case behavior, unfiltered
152 
153  // write the latest prediction set for desired behavior
155 
156  // read the latest conflict set
158 
159  // read the latest conflict set
161 
162 
163  // // read lane geometry
165 
166  // write lane geometry
168 
169  // read reset signal for lane matching
171 
172  // writer reset signal for lane matching
174 
175  // write speed limit info
177 
178  // get speed limit feed
180  // write the area of effect
182  // write the area of interest
184 
185  // read cooperative users prediction
187 
188  // write cooperative users prediction
190 
191  // read cooperative users list prediction
193 
194  // write cooperative users list prediction
196 
197  // write the gap queue on the left lane
199  // write the gap queue on the right lane
201  // read the gap queue on the left lane
203  // read the gap queue on the right lane
205 
206  // write indicator hint info
208 
209  // get indicator hint feed
211  };
212 
213 
219  class EnvFactoryInstance final
220  {
221  private:
223 
230  {
231  static EnvFactoryInstance instance;
232  return instance;
233  }
234 
235  public:
237  {
238  if (getInstance().envFactory_ == 0)
239  {
240  std::cerr << " WARNING Accessing singleton envFactory instance without ever running init()"
241  << std::endl;
242  }
243  return getInstance().envFactory_;
244  }
245 
254  static void init(adore::env::AFactory* envFactory)
255  {
256  auto& instance = getInstance();
257  instance.envFactory_ = envFactory;
258  }
259 
260  private:
261  EnvFactoryInstance() = default;
262  ~EnvFactoryInstance() = default;
263 
268  };
269 
270  }
271 }
abstract factory for adore::env communication
Definition: afactory.h:41
virtual TParticipantSetReader * getTrafficParticipantSetReader()=0
virtual TResetLaneMatchingReader * getResetLaneMatchingReader()=0
virtual TControlledConnectionFeed * getCheckPointFeed()=0
virtual TControlledConnectionWriter * getCheckPointWriter()=0
adore::mad::AWriter< std::pair< adore::env::BorderBased::BorderID, double > > TNavgationDataWriter
Definition: afactory.h:50
virtual TPrecedenceRuleWriter * getPrecedenceRuleWriter()=0
virtual TOCPredictionSetWriter * getWorstCasePredictionSetWriter()=0
virtual TSpeedLimitFeed * getSpeedLimitFeed()=0
adore::mad::AWriter< adore::env::IndicatorHint > TIndicatorHintWriter
Definition: afactory.h:73
virtual TIndicatorHintFeed * getIndicatorHintFeed()=0
adore::mad::AReader< bool > TResetLaneMatchingReader
Definition: afactory.h:62
virtual TAreaOfEffectWriter * getAreaOfInterestWriter()=0
adore::mad::AReader< OccupancyCylinderPredictionSet > TOCPredictionSetReader
Definition: afactory.h:58
virtual TOCPredictionSetWriter * getConflictSetWriter()=0
adore::mad::AFeed< ControlledConnection > TControlledConnectionFeed
Definition: afactory.h:56
virtual TBorderTypeChangeProfileFeed * getBorderTypeChangeProfileFeed()=0
virtual TPropositionWriter * getPropositionWriter()=0
virtual TNavigationGoalReader * getNavigationGoalReader()=0
adore::mad::AWriter< CooperativeUsersList > CooperativeUsersListWriter
Definition: afactory.h:70
virtual TOCPredictionSetReader * getExpectedPredictionSetReader()=0
virtual TOCPredictionSetReader * getExpectedRawPredictionSetReader()=0
adore::mad::AReader< VehicleMotionState9d > TVehicleMotionStateReader
Definition: afactory.h:47
adore::mad::AFeed< BorderBased::Border > TBorderFeed
Definition: afactory.h:43
virtual TNavigationDataFeed * getNavigationDataFeed()=0
virtual TOCPredictionSetReader * getStaticObstaclesPredictionSetReader()=0
adore::mad::AWriter< adore::env::AreaOfEffect > TAreaOfEffectWriter
Definition: afactory.h:66
adore::mad::AFeed< adore::env::PrecedenceRule > TPrecedenceRuleFeed
Definition: afactory.h:53
virtual TGapQueueReader * getGapQueueReaderRightLane()=0
virtual TOCPredictionSetWriter * getDesiredPredictionSetWriter()=0
adore::mad::AReader< traffic::TParticipantSet > TParticipantSetReader
Definition: afactory.h:48
adore::mad::AFeed< adore::env::SpeedLimit > TSpeedLimitFeed
Definition: afactory.h:65
adore::mad::AFeed< BorderTypeChangeProfile > TBorderTypeChangeProfileFeed
Definition: afactory.h:44
virtual CooperativeUsersListWriter * getCooperativeUsersListWriter()=0
virtual TSpeedLimitWriter * getSpeedLimitWriter()=0
adore::mad::AFeed< std::pair< adore::env::BorderBased::BorderID, double > > TNavigationDataFeed
Definition: afactory.h:51
adore::mad::AWriter< OccupancyCylinderPredictionSet > TOCPredictionSetWriter
Definition: afactory.h:59
adore::mad::AWriter< adore::env::BorderBased::CombinedLaneGeometry > TLaneGeometryWriter
Definition: afactory.h:61
adore::mad::AReader< CooperativeUsersList > CooperativeUsersListReader
Definition: afactory.h:69
virtual TVehicleMotionStateReader * getVehicleMotionStateReader()=0
adore::mad::AWriter< adore::env::SpeedLimit > TSpeedLimitWriter
Definition: afactory.h:64
virtual CooperativeUserWriter * getCooperativeUserWriter()=0
virtual TGapQueueWriter * getGapQueueWriterLeftLane()=0
virtual TLaneGeometryWriter * getLaneGeometryWriter()=0
virtual TPrecedenceRuleFeed * getPrecedenceRuleFeed()=0
adore::mad::AFeed< adore::env::BorderBased::CombinedLaneGeometry > TLaneGeometryFeed
Definition: afactory.h:60
adore::mad::AWriter< adore::env::PrecedenceRule > TPrecedenceRuleWriter
Definition: afactory.h:52
virtual TOCPredictionSetReader * getConflictSetReader()=0
adore::mad::AWriter< Proposition > TPropositionWriter
Definition: afactory.h:54
adore::mad::AWriter< BorderBased::Border > TBorderWriter
Definition: afactory.h:46
virtual TBorderTypeChangeProfileWriter * getBorderTypeChangeProfileWriter()=0
virtual TLaneGeometryFeed * getLaneGeometryFeed()=0
virtual TPropositionFeed * getPropositionFeed()=0
virtual TOCPredictionSetReader * getWorstCaseRawPredictionSetReader()=0
virtual TGapQueueWriter * getGapQueueWriterRightLane()=0
adore::mad::AReader< adore::env::GapQueue > TGapQueueReader
Definition: afactory.h:72
adore::mad::AReader< adore::fun::NavigationGoal > TNavigationGoalReader
Definition: afactory.h:49
virtual TOCPredictionSetWriter * getExpectedPredictionSetWriter()=0
virtual TControlledConnectionFeed * getControlledConnectionFeed()=0
virtual TAreaOfEffectWriter * getAreaOfEffectWriter()=0
adore::mad::AWriter< bool > TResetLaneMatchingWriter
Definition: afactory.h:63
virtual TOCPredictionSetWriter * getWorstCaseRawPredictionSetWriter()=0
adore::mad::AWriter< ControlledConnection > TControlledConnectionWriter
Definition: afactory.h:57
virtual TIndicatorHintWriter * getIndicatorHintWriter()=0
virtual TOCPredictionSetReader * getWorstCasePredictionSetReader()=0
adore::mad::AFeed< Proposition > TPropositionFeed
Definition: afactory.h:55
adore::mad::AWriter< BorderTypeChangeProfile > TBorderTypeChangeProfileWriter
Definition: afactory.h:45
virtual TResetLaneMatchingWriter * getResetLaneMatchingWriter()=0
virtual TOCPredictionSetReader * getDesiredPredictionSetReader()=0
virtual TGapQueueReader * getGapQueueReaderLeftLane()=0
virtual CooperativeUsersListReader * getCooperativeUsersListReader()=0
adore::mad::AReader< CooperativeUserPrediction > CooperativeUserReader
Definition: afactory.h:67
adore::mad::AFeed< adore::env::IndicatorHint > TIndicatorHintFeed
Definition: afactory.h:74
adore::mad::AWriter< CooperativeUserPrediction > CooperativeUserWriter
Definition: afactory.h:68
virtual TOCPredictionSetWriter * getExpectedRawPredictionSetWriter()=0
virtual CooperativeUserReader * getCooperativeUserReader()=0
virtual TBorderWriter * getBorderWriter()=0
adore::mad::AWriter< adore::env::GapQueue > TGapQueueWriter
Definition: afactory.h:71
virtual TNavgationDataWriter * getNavigationDataWriter()=0
virtual TBorderFeed * getBorderFeed()=0
Utility class to simplify factory access.
Definition: afactory.h:220
static adore::env::AFactory * get()
Definition: afactory.h:236
adore::env::AFactory * envFactory_
Definition: afactory.h:222
static EnvFactoryInstance & getInstance()
Function to access singleton instance of the envFactory using magic static.
Definition: afactory.h:229
EnvFactoryInstance & operator=(EnvFactoryInstance &&)=delete
EnvFactoryInstance(EnvFactoryInstance &&)=delete
EnvFactoryInstance(const EnvFactoryInstance &)=delete
static void init(adore::env::AFactory *envFactory)
Initialize private members of AllFactory.
Definition: afactory.h:254
EnvFactoryInstance & operator=(const EnvFactoryInstance &)=delete
Definition: com_patterns.h:29
Definition: com_patterns.h:68
Definition: com_patterns.h:97
Definition: areaofeffectconverter.h:20