sync.hpp 1.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849
  1. #ifndef _SYNC_HEADER_
  2. #define _SYNC_HEADER_
  3. #include "ros/ros.h"
  4. #include <boost/circular_buffer.hpp>
  5. #include <ros/callback_queue.h>
  6. #include <pthread.h>
  7. template<typename T1, typename T2, typename T3>
  8. class Synchronizer
  9. {
  10. public:
  11. Synchronizer(const std::string sub1_topic, const std::string sub2_topic, const std::string pub1_topic, const std::string pub2_topic, const std::string req_topic, const std::string ns);
  12. void run();
  13. private:
  14. bool buf_flag_;
  15. pthread_mutex_t mutex_;
  16. /* user var */
  17. boost::circular_buffer<T1> type1_ringbuf_;
  18. boost::circular_buffer<T2> type2_ringbuf_;
  19. ros::Publisher type1_pub_;
  20. ros::Publisher type2_pub_;
  21. ros::Publisher sync_time_diff_pub_;
  22. bool is_req_;
  23. T1* p_type1_buf_;
  24. T2* p_type2_buf_;
  25. ros::Subscriber type1_sub_;
  26. ros::Subscriber type2_sub_;
  27. #if 0
  28. ros::Subscriber req_sub_;
  29. ros::CallbackQueue rcv_callbackqueue_;
  30. #endif
  31. std::string req_topic_;
  32. void publish_msg(T1* p_type1_buf_, T2* p_type2_buf_);
  33. bool publish();
  34. void type1_callback(const typename T1::ConstPtr& type1_msg);
  35. void type2_callback(const typename T2::ConstPtr& type2_msg);
  36. void req_callback(const typename T3::ConstPtr& req_msg);
  37. static void* launchThread(void *args) {
  38. reinterpret_cast<Synchronizer<T1,T2,T3>*>(args)->thread();
  39. pthread_exit(NULL);
  40. }
  41. void thread();
  42. };
  43. #include "impl/sync_impl.hpp"
  44. #endif