wander.cpp
Go to the documentation of this file.
00001 /*
00002 Author: Minglong Li
00003 Affiliation: State Key Laboratory of High Performance Computing (HPCL)
00004              College of Computer, National University of Defense Technology
00005 Email: minglong_l@163.com
00006 Created on: July 17th, 2016
00007 */
00008 
00009 #include <ros/ros.h>
00010 #include <nodelet/nodelet.h>
00011 #include <iostream>
00012 #include <stdlib.h>
00013 #include <time.h>
00014 
00015 #include <pluginlib/class_list_macros.h>
00016 
00017 #include <micros_mars_task_alloc/Heading.h>
00018 
00019 namespace micros_mars_task_alloc {
00020 using namespace std;
00021 
00022 class Wander : public nodelet::Nodelet
00023 {
00024 public:
00025     Wander():forward_distance_(3.0){}
00026     ~Wander(){}
00027 
00028     virtual void onInit();
00029     void timerCallback(const ros::TimerEvent&);
00030         
00031 private:
00032     float forward_distance_;
00033     
00034     ros::NodeHandle nh_;
00035     ros::Timer timer_;
00036     ros::Publisher pub_;
00037 };
00038 
00039 void Wander::onInit()
00040 {
00041     nh_ = getPrivateNodeHandle();
00042     pub_ = nh_.advertise<micros_mars_task_alloc::Heading>("/wander/heading", 10);
00043     cout << "Initialising nodelet ..." << endl;
00044     timer_ = nh_.createTimer(ros::Duration(1.0), &Wander::timerCallback, this);
00045 }
00046 
00047 void Wander::timerCallback(const ros::TimerEvent&)
00048 {
00049     micros_mars_task_alloc::HeadingPtr heading_ptr(new micros_mars_task_alloc::Heading);
00050     heading_ptr->distance = forward_distance_;
00051     srand(time(NULL));
00052     heading_ptr->angle = (-1000 + rand()%2000)/1000.0; 
00053     pub_.publish(heading_ptr);
00054 }
00055 }//namespace micros_mars_task_alloc
00056 PLUGINLIB_EXPORT_CLASS(micros_mars_task_alloc::Wander, 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