JobScheduler  1.1.0
CMJob_RosSubscriber.h
1 #pragma once
2 
3 #include <functional>
4 
5 #include "CMJob.h"
6 #include "ros/ros.h"
7 
8 namespace CMJob {
9 
14 template <typename T>
15 class RosSubscriber final : public AbstractJob {
16  public:
17  RosSubscriber<T>(const JobType& type, const bool& sync,
18  const ros::NodeHandlePtr& node, const std::string& topic,
19  const size_t& queue_size = 1)
20  : AbstractJob(topic, type, sync),
21  node_(node),
22  topic_(topic),
23  queue_size_(queue_size) {}
24 
28  void init(void);
29 
33  void execute(void);
34 
39  void registerCallback(std::function<void(const T&)> fp) {
40  user_callback_ = std::bind(fp, std::placeholders::_1);
41  }
42 
49  template <typename M>
50  void registerCallback(void (M::*fp)(const T&), M* obj) {
51  user_callback_ = std::bind(fp, obj, std::placeholders::_1);
52  }
53 
58  void rosCallback(const T& msg);
59 
60  private:
61  ros::NodeHandlePtr node_ = nullptr;
63  std::string topic_;
64  ros::Subscriber sub_;
65  size_t queue_size_ = 1;
67  std::function<void(const T&)> user_callback_;
68  T msg_;
69 };
70 
72 // IMPLEMENTATION //
74 
75 template <typename T>
77  /* add ros subscriber */
78  this->sub_ = this->node_->subscribe(this->topic_, this->queue_size_,
80 
82 }
83 
84 template <typename T>
86  if (this->user_callback_ && this->msg_ != nullptr) {
87  this->user_callback_(this->msg_);
88  }
89 
91 }
92 
93 template <typename T>
94 void RosSubscriber<T>::rosCallback(const T& msg) {
95  if (this->getJobState() == JobState::Disabled) return;
96 
97  this->msg_ = msg;
98  prepare();
99 
100  if (this->getCallbackHook() == CallbackHook::Manual) {
101  execute();
102  }
103 }
104 
105 } // namespace CMJob
void execute(void)
Execution of the job.
Definition: CMJob_RosSubscriber.h:85
Library for providing a generic interface to handle jobs.
virtual void prepare()
Preperation of the job.
Definition: Job.cpp:269
Ros_Subscriber provides a job based interfoce for ros subscribers.
Definition: CMJob_RosSubscriber.h:15
virtual void execute()=0
Execution of the job.
Definition: Job.cpp:271
Definition: CMJob.h:16
void init(void)
Initialization of the job.
Definition: CMJob_RosSubscriber.h:76
void rosCallback(const T &msg)
callback function, which is used for the ros subscriber
Definition: CMJob_RosSubscriber.h:94
JobType
Definition: CMJob.h:30
void registerCallback(std::function< void(const T &)> fp)
register_callback
Definition: CMJob_RosSubscriber.h:39
void registerCallback(void(M::*fp)(const T &), M *obj)
register_callback
Definition: CMJob_RosSubscriber.h:50
virtual void init()
Initialization of the job.
Definition: Job.cpp:258
AbstractJob(const std::string &name, JobType type, bool sync)
AbstractJob.
Definition: Job.cpp:43
The AbstractJob class provides an interface for jobs.
Definition: CMJob.h:74