16 RosPublisher<T>(
const ros::NodeHandlePtr& node,
const std::string& topic,
17 const size_t& queue_size = 1)
21 queue_size_(queue_size) {
23 initPublisher(tag<T>{});
38 user_callback_ = std::bind(fp, std::placeholders::_1);
49 user_callback_ = std::bind(fp, obj, std::placeholders::_1);
53 ros::NodeHandlePtr node_ =
nullptr;
57 size_t queue_size_ = 1;
59 std::function<void(T&)> user_callback_;
67 void initPublisher(tag<R>) {
69 this->node_->template advertise<R>(this->topic_, this->queue_size_);
73 void initPublisher(tag<boost::shared_ptr<R>>) {
75 this->node_->template advertise<R>(this->topic_, this->queue_size_);
79 void initMsg(tag<R>) {}
82 void initMsg(tag<boost::shared_ptr<R>>) {
83 this->msg_ = boost::make_shared<R>();
93 if (this->user_callback_ && this->msg_ !=
nullptr) {
94 this->user_callback_(this->msg_);
95 this->pub_.publish(this->msg_);
void registerCallback(void(M::*fp)(T &), M *obj)
register_callback
Definition: CMJob_RosPublisher.h:48
Ros_Publisher provides a job based interfoce for ros publisher.
Definition: CMJob_RosPublisher.h:14
void registerCallback(std::function< void(T &)> fp)
register_callback
Definition: CMJob_RosPublisher.h:37
called periodically at the end of the job
Library for providing a generic interface to handle jobs.
void execute(void)
Execution of the job.
Definition: CMJob_RosPublisher.h:92
virtual void execute()=0
Execution of the job.
Definition: Job.cpp:271
void setCallbackHook(CallbackHook hook)
setCallbackHook
Definition: Job.cpp:131
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