status.cpp
Go to the documentation of this file.
00001 /*************************************************************************
00002         > File Name: status.cpp
00003         > Author: Minglong Li
00004         > Mail: minglong_l@163.com
00005     > Created on: 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 
00013 #include<std_msgs/Bool.h>
00014 
00015 namespace micros_mars_task_alloc{
00016     using namespace std;
00017     
00018     class Status : public nodelet::Nodelet
00019     {
00020     public:
00021         Status(){}
00022         ~Status(){}
00023 
00024         virtual void onInit();
00025         void callback(const std_msgs::BoolConstPtr & msg);
00026     private:
00027         ros::NodeHandle nh_;
00028         ros::Subscriber sub_;
00029         ros::Publisher pub_;
00030     };
00031 
00032     void Status::onInit()
00033     {
00034         nh_ = getPrivateNodeHandle();
00035         cout << "Initialising nodelet ..." << endl;
00036 
00037         sub_ = nh_.subscribe("/robot/busy", 10, &Status::callback, this);//the topic is a absolute topic.
00038         pub_ = nh_.advertise<std_msgs::Bool>("busy", 10);//the topic is a relative topic, and the prefix "status" will be added.
00039     }
00040     void Status::callback(const std_msgs::BoolConstPtr & msg)
00041     {
00042         ros::Rate rate(10);
00043         int count = 0;
00044         std_msgs::BoolPtr bool_ptr(new std_msgs::Bool);
00045         bool_ptr -> data = msg -> data;
00046         pub_.publish(bool_ptr);
00047         /*
00048         while (ros::ok())
00049         {
00050             std_msgs::BoolPtr bool_ptr(new std_msgs::Bool);
00051             bool_ptr -> data = msg -> data;
00052             pub_.publish(bool_ptr);
00053             count += 1;
00054             rate.sleep();
00055             if (count == 5)
00056             {
00057                 count = 0;
00058                 break;
00059             }
00060         }
00061         */
00062     }
00063 }//namespace micros_mars_task_alloc
00064 PLUGINLIB_EXPORT_CLASS(micros_mars_task_alloc::Status, 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