whenlook.cpp
Go to the documentation of this file.
00001 /*************************************************************************
00002         > File Name: whenlook.cpp
00003         > Author: Minglong Li
00004         > Mail: minglong_l@163.com
00005         > Created Time: July 18th, 2016
00006  ************************************************************************/
00007 
00008 #include<iostream>
00009 #include<ros/ros.h>
00010 #include<nodelet/nodelet.h>
00011 #include<pluginlib/class_list_macros.h>
00012 #include<std_msgs/Bool.h>
00013 
00014 namespace micros_mars_task_alloc{
00015     class Whenlook : public nodelet::Nodelet{
00016     public:
00017         virtual void onInit();
00018         void callback(const std_msgs::BoolConstPtr & msg);
00019     private:
00020         ros::NodeHandle nh_;
00021         ros::Subscriber sub_;
00022         ros::Publisher pub_;
00023     };
00024     
00025     void Whenlook::onInit()
00026     {
00027         nh_ = getPrivateNodeHandle();
00028         sub_ = nh_.subscribe("/status/busy", 10, &Whenlook::callback, this);//this topic is an absolute topic
00029         pub_ = nh_.advertise<std_msgs::Bool>("startlook", 10);//this topic is a relative topic, the prefix whenlook will be added.
00030     }
00031     void Whenlook::callback(const std_msgs::BoolConstPtr & msg)
00032     {
00033         if (msg->data == false)
00034         {
00035             std_msgs::BoolPtr bool_ptr(new std_msgs::Bool);
00036             bool_ptr -> data = true;
00037             pub_.publish(bool_ptr);
00038         }
00039     }
00040 }//namespace micros_mars_task_alloc
00041 PLUGINLIB_EXPORT_CLASS(micros_mars_task_alloc::Whenlook, nodelet::Nodelet)


micros_mars_task_alloc
Author(s): Minglong Li , Xiaodong Yi , Yanzhen Wang , Zhongxuan Cai
autogenerated on Mon Jul 1 2019 19:55:03