Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008 #ifndef SUPPRESSOR_H_
00009 #define SUPPRESSOR_H_
00010
00011 #include <ros/ros.h>
00012 #include <nodelet/nodelet.h>
00013 #include <iostream>
00014 #include <pluginlib/class_list_macros.h>
00015
00016 namespace micros_mars_task_alloc {
00017
00018 template<typename MsgType>
00019 class Suppressor : public nodelet::Nodelet
00020 {
00021
00022
00023 public:
00024 Suppressor(){}
00025 virtual ~Suppressor(){}
00026 virtual void onInit()
00027 {
00028 nh_ = getPrivateNodeHandle();
00029 std::cout << "Initialising nodelet ..." << std::endl;
00030
00031
00032
00033
00034
00035
00036
00037
00038 if (!(nh_.getParam("upper_topic", upper_topic_)))
00039 {
00040 std::cout << "Fail to get the parameter upper_topic." << std::endl;
00041 return;
00042 }
00043 if (!(nh_.getParam("lower_topic", lower_topic_)))
00044 {
00045 std::cout << "Fail to get the parameter lower_topic" << std::endl;
00046 return;
00047 }
00048 if (!(nh_.getParam("output_topic",output_topic_)))
00049 {
00050 std::cout << "Fail to get the parameter output_topic" << std::endl;
00051 return;
00052 }
00053 nh_.param<double>("time_duration", time_duration_, 1.0);
00054 upper_msg_sub_ = nh_.subscribe(upper_topic_, 10, &Suppressor::upperCB, this);
00055 lower_msg_sub_ = nh_.subscribe(lower_topic_, 10, &Suppressor::lowerCB, this);
00056 pub_ = nh_.advertise<MsgType>(output_topic_, 10);
00057
00058 }
00059
00060 void upperCB(const boost::shared_ptr<const MsgType>& msg)
00061 {
00062 begin_ = ros::Time::now().toSec();
00063
00064 pub_.publish(msg);
00065 std::cout << "The upper layer messages output successfully." << std::endl;
00066 };
00067
00068
00069 void lowerCB(const boost::shared_ptr<const MsgType>& msg)
00070 {
00071 end_ = ros::Time::now().toSec();
00072 if(end_-begin_ > time_duration_)
00073 {
00074
00075 pub_.publish(msg);
00076 std::cout << "the lower layer messages output successfully." << std::endl;
00077 }
00078 };
00079
00080 private:
00081 ros::NodeHandle nh_;
00082 std::string upper_topic_, lower_topic_, output_topic_;
00083 ros::Subscriber upper_msg_sub_, lower_msg_sub_;
00084 ros::Publisher pub_;
00085 double begin_;
00086 double end_;
00087 double time_duration_;
00088
00089 };
00090
00091 }
00092 #endif