Node.hpp
Go to the documentation of this file.
1 
7 #pragma once
8 
9 #include <ros/ros.h>
10 #include <sched.h>
11 #include <unistd.h> // for getpid()
12 #include <memory> // for std::shared_ptr
13 
16 
17 namespace bota_node
18 {
19 bool setProcessPriority(int priority);
20 
21 class Node
22 {
23 public:
24  using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
25 
26  Node() = delete;
27  explicit Node(NodeHandlePtr nh);
28  virtual ~Node() = default;
29 
30  /*
31  * (abstract) interface functions
32  */
33 
38  virtual bool init() = 0;
43  virtual void preCleanup()
44  {
45  }
50  virtual void cleanup() = 0;
51 
52  /*
53  * general
54  */
55 
59  void shutdown();
60 
64  template <class T>
65  inline bool addWorker(const std::string& name, const double timestep, bool (T::*fp)(const bota_worker::WorkerEvent&),
66  T* obj, const int priority = 0)
67  {
68  return workerManager_.addWorker(name, timestep, fp, obj, priority);
69  }
70 
71  inline bool addWorker(const bota_worker::WorkerOptions& options)
72  {
73  return workerManager_.addWorker(options);
74  }
75 
81  inline bool hasWorker(const std::string& name)
82  {
83  return workerManager_.hasWorker(name);
84  }
85 
91  inline void cancelWorker(const std::string& name, const bool wait = true)
92  {
93  workerManager_.cancelWorker(name, wait);
94  }
95 
99  inline void stopAllWorkers()
100  {
101  stopAllWorkers(true);
102  }
103  inline void stopAllWorkers(bool wait)
104  {
106  }
107 
108  /*
109  * accessors
110  */
112  {
113  return *nh_;
114  }
115 
116 protected:
118 
119 private:
121 };
122 
123 } // namespace bota_node
bool hasWorker(const std::string &name)
void stopAllWorkers(bool wait)
Definition: Node.hpp:103
void shutdown()
Definition: Node.cpp:17
virtual ~Node()=default
virtual void preCleanup()
Definition: Node.hpp:43
NodeHandlePtr nh_
Definition: Node.hpp:117
ros::NodeHandle & getNodeHandle() const
Definition: Node.hpp:111
bool hasWorker(const std::string &name)
Definition: Node.hpp:81
virtual void cleanup()=0
bool addWorker(const std::string &name, const double timestep, bool(T::*fp)(const bota_worker::WorkerEvent &), T *obj, const int priority=0)
Definition: Node.hpp:65
void cancelWorkers(const bool wait=true)
virtual bool init()=0
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
Definition: Node.hpp:24
bool addWorker(const bota_worker::WorkerOptions &options)
Definition: Node.hpp:71
bota_worker::WorkerManager workerManager_
Definition: Node.hpp:120
void cancelWorker(const std::string &name, const bool wait=true)
Definition: Node.hpp:91
bool setProcessPriority(int priority)
Definition: Node.cpp:24
bool addWorker(const std::string &name, const double timestep, bool(T::*fp)(const WorkerEvent &), T *obj, const int priority=0, const bool autostart=true)
void cancelWorker(const std::string &name, const bool wait=true)
void stopAllWorkers()
Definition: Node.hpp:99


bota_node
Author(s):
autogenerated on Wed Mar 3 2021 03:09:11