EEROS  1.0.0.0
API for the EEROS Real-Time Robotics Framework
SafetySystem.hpp
Go to the documentation of this file.
1 #ifndef ORG_EEROS_SAFETY_SAFETYSYSTEM_HPP_
2 #define ORG_EEROS_SAFETY_SAFETYSYSTEM_HPP_
3 
4 #include <vector>
5 #include <mutex>
10 #include <eeros/logger/Logger.hpp>
12 
13 namespace eeros {
14  namespace safety {
19  class SafetySystem : public Runnable {
20  public:
26  SafetySystem(SafetyProperties& properties, double period);
30  virtual ~SafetySystem();
42  void triggerEvent(SafetyEvent event, SafetyContext* context = nullptr);
47  const SafetyProperties* getProperties() const;
52  double getPeriod() const;
56  void run();
61  static void exitHandler();
64  private:
65  bool setProperties(SafetyProperties& safetyProperties);
66  std::mutex mtx;
67  SafetyProperties properties;
68  SafetyLevel* currentLevel;
69  SafetyLevel* nextLevel;
70  SafetyContext privateContext;
71  static uint8_t instCount;
72  static SafetySystem* instance;
73  double period;
74  };
75 
76  };
77 };
78 
79 #endif // ORG_EEROS_SAFETY_SAFETYSYSTEM_HPP_
Safety system.
Definition: SafetySystem.hpp:19
Definition: Logger.hpp:15
Definition: SafetyLevel.hpp:33
double getPeriod() const
Definition: SafetySystem.cpp:78
Definition: Config.hpp:14
static void exitHandler()
Definition: SafetySystem.cpp:126
Definition: Runnable.hpp:6
Definition: SafetyContext.hpp:12
void run()
Definition: SafetySystem.cpp:82
virtual ~SafetySystem()
Definition: SafetySystem.cpp:24
SafetySystem(SafetyProperties &properties, double period)
Definition: SafetySystem.cpp:10
const SafetyProperties * getProperties() const
Definition: SafetySystem.cpp:74
SafetyLevel & getCurrentLevel(void)
Definition: SafetySystem.cpp:28
void triggerEvent(SafetyEvent event, SafetyContext *context=nullptr)
Definition: SafetySystem.cpp:49
Definition: SafetyProperties.hpp:15
Definition: SafetyLevel.hpp:21
logger::Logger log
Definition: SafetySystem.hpp:62