18 const ros::NodeHandlePtr& node,
const std::string& topic,
19 const size_t& queue_size = 1)
23 queue_size_(queue_size) {}
40 user_callback_ = std::bind(fp, std::placeholders::_1);
51 user_callback_ = std::bind(fp, obj, std::placeholders::_1);
61 ros::NodeHandlePtr node_ =
nullptr;
65 size_t queue_size_ = 1;
67 std::function<void(const T&)> user_callback_;
78 this->sub_ = this->node_->subscribe(this->topic_, this->queue_size_,
86 if (this->user_callback_ && this->msg_ !=
nullptr) {
87 this->user_callback_(this->msg_);
95 if (this->getJobState() == JobState::Disabled)
return;
100 if (this->getCallbackHook() == CallbackHook::Manual) {
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
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