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 
17 #include <adore/mad/com_patterns.h>
30 
32 
33 namespace adore
34 {
39  namespace sim
40  {
42  class AFactory
43  {
44  public:
69 
70 
95  //send simulation commands for vehicle position and orientation resetting
121  };
122 
128  class SimFactoryInstance final
129  {
130  private:
132 
139  {
140  static SimFactoryInstance instance;
141  return instance;
142  }
143 
144  public:
146  {
147  if (getInstance().factory_ == nullptr)
148  {
149  std::cerr << " WARNING Accessing singleton simFactory instance without ever running init()"
150  << std::endl;
151  }
152  return getInstance().factory_;
153  }
154 
162  static void init(adore::sim::AFactory* factory)
163  {
164  auto& instance = getInstance();
165  instance.factory_ = factory;
166  }
167 
168  private:
169  SimFactoryInstance() = default;
170  ~SimFactoryInstance() = default;
171 
176  };
177  }
178 }
Definition: com_patterns.h:46
Definition: com_patterns.h:97
abstract factory for adore::sim communication
Definition: afactory.h:43
virtual TSimulationTimeWriter * getSimulationTimeWriter()=0
write the simulation time
virtual TSimulationIDResetFeed * getSimulationIDResetFeed()=0
read simulation commands for simulation id resetting
adore::mad::AReader< adore::env::SimTrafficLightMap > TSimTrafficLightReader
Definition: afactory.h:66
virtual TVehicleMotionStateWriter * getVehicleMotionStateWriter()=0
write updates on the true vehicle motion state
adore::mad::AWriter< std::pair< uint32_t, uint32_t > > TClockTimeWriter
Definition: afactory.h:64
virtual TGearSelectionCommandReader * getGearSelectionCommandReader()=0
read a gear selection command
virtual TVehicleMotionStateReader * getVehicleMotionStateReader()=0
read updates on the true vehicle motion state
adore::mad::AWriter< double > TSimulationTimeWriter
Definition: afactory.h:49
adore::mad::AWriter< adore::sim::ResetVehiclePose > TVehiclePoseResetWriter
Definition: afactory.h:55
adore::mad::AWriter< adore::env::traffic::TParticipantSet > TParticipantSetWriter
Definition: afactory.h:61
adore::mad::AWriter< adore::fun::VehicleExtendedState > TVehicleExtendedStateWriter
Definition: afactory.h:52
virtual TVehicleMotionStateWriter * getOdometryEstimatedVehicleStateWriter()=0
write updates on the odometry estimated vehicle motion state
virtual TClockTimeWriter * getClockTimeWriter()=0
write clock time
virtual TVehicleTwistResetWriter * getVehicleTwistResetWriter()=0
send simulation commands for vehicle speed resetting
adore::mad::AReader< adore::fun::VehicleMotionState9d > TVehicleMotionStateReader
Definition: afactory.h:51
adore::mad::AReader< adore::fun::MotionCommand > TMotionCommandReader
Definition: afactory.h:45
virtual TVehicleMotionStateWriter * getLocalizationEstimatedVehicleStateWriter()=0
write updates on the localization estimated vehicle motion state
virtual TVehicleDimensionsResetFeed * getVehicleDimensionsResetFeed()=0
read simulation commands for vehicle dimensions resetting
virtual TSimTrafficLightWriter * getTrafficLightWriter()=0
send simulated traffic light states
adore::mad::AFeed< adore::sim::ResetVehiclePose > TVehiclePoseResetFeed
Definition: afactory.h:53
adore::mad::AFeed< int64_t > TSimulationIDResetFeed
Definition: afactory.h:57
adore::mad::AWriter< adore::sim::ResetVehicleDimensions > TVehicleDimensionsResetWriter
Definition: afactory.h:59
adore::mad::AFeed< adore::sim::ResetVehicleDimensions > TVehicleDimensionsResetFeed
Definition: afactory.h:60
virtual TMotionCommandReader * getMotionCommandReader()=0
read a motion command
adore::mad::AFeed< adore::env::traffic::Participant > TParticipantFeed
Definition: afactory.h:63
adore::mad::AWriter< adore::fun::VehicleMotionState9d > TVehicleMotionStateWriter
Definition: afactory.h:50
adore::mad::AReader< adore::fun::GearSelectionCommand > TGearSelectionCommandReader
Definition: afactory.h:46
virtual adore::mad::AWriter< int64_t > * getTransformIDtoAdoreWriter()=0
send id of vehicle to transform
virtual TVehicleDimensionsResetWriter * getVehicleDimensionsResetWriter(std::string ns)=0
write simulation command for vehicle dimensions resetting
virtual TSimTrafficLightReader * getTrafficLightReader()=0
receive simulated traffic light states
adore::mad::AWriter< adore::env::SimTrafficLight > TSimTrafficLightWriter
Definition: afactory.h:65
virtual TParticipantFeed * getParticipantFeed()=0
get state updates from all vehicles
adore::mad::AWriter< std::string > TSimulationCoordinationWriter
Definition: afactory.h:68
virtual TVehiclePoseResetFeed * getVehiclePoseResetFeed()=0
read simulation commands for vehicle position and orientation resetting
adore::mad::AReader< adore::fun::IndicatorCommand > TIndicatorCommandReader
Definition: afactory.h:47
adore::mad::AWriter< adore::env::traffic::Participant > TParticipantWriter
Definition: afactory.h:62
virtual TParticipantSetWriter * getParticipantSetWriter()=0
send simulated sensor data
adore::mad::AFeedWithCallback< std::string > TSimulationCoordinationFeed
Definition: afactory.h:67
adore::mad::AFeed< adore::sim::ResetVehicleTwist > TVehicleTwistResetFeed
Definition: afactory.h:54
virtual TVehicleTwistResetFeed * getVehicleTwistResetFeed()=0
read simulation commands for vehicle speed resetting
virtual TVehiclePoseResetWriter * getVehiclePoseResetWriter()=0
virtual TVehicleExtendedStateWriter * getVehicleExtendedStateWriter()=0
write updates on the vehicle extended state (buttons, etc.)
adore::mad::AFeed< int64_t > TV2XStationIDResetFeed
Definition: afactory.h:58
virtual TSimulationTimeReader * getSimulationTimeReader()=0
read the simulation time
virtual TParticipantWriter * getParticipantWriter()=0
send ego state to simulation feed
virtual TV2XStationIDResetFeed * getV2XStationIDResetFeed()=0
read simulation commands for v2x station id resetting
virtual TIndicatorCommandReader * getIndicatorCommandReader()=0
read an indicator command
adore::mad::AWriter< adore::sim::ResetVehicleTwist > TVehicleTwistResetWriter
Definition: afactory.h:56
adore::mad::AReader< double > TSimulationTimeReader
Definition: afactory.h:48
Utility class to simplify factory access.
Definition: afactory.h:129
adore::sim::AFactory * factory_
Definition: afactory.h:131
static SimFactoryInstance & getInstance()
Function to access singleton instance of the AllFactory using magic static.
Definition: afactory.h:138
static adore::sim::AFactory * get()
Definition: afactory.h:145
SimFactoryInstance(SimFactoryInstance &&)=delete
SimFactoryInstance & operator=(SimFactoryInstance &&)=delete
SimFactoryInstance(const SimFactoryInstance &)=delete
static void init(adore::sim::AFactory *factory)
Initialize private members of AllFactory.
Definition: afactory.h:162
SimFactoryInstance & operator=(const SimFactoryInstance &)=delete
Definition: areaofeffectconverter.h:20