one_shot_timer.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef ACTIONLIB__ONE_SHOT_TIMER_H_
36 #define ACTIONLIB__ONE_SHOT_TIMER_H_
37 
38 #include "ros/ros.h"
39 #include "boost/bind.hpp"
40 
43 {
44 public:
46  : active_(false) {}
47 
48  void cb(const ros::TimerEvent & e)
49  {
50  if (active_) {
51  active_ = false;
52 
53  if (callback_) {
54  callback_(e);
55  } else {
56  ROS_ERROR_NAMED("actionlib", "Got a NULL Timer OneShotTimer Callback");
57  }
58  }
59  }
60 
61  boost::function<void(const ros::TimerEvent & e)> getCb()
62  {
63  return boost::bind(&OneShotTimer::cb, this, _1);
64  }
65 
66  void registerOneShotCb(boost::function<void(const ros::TimerEvent & e)> callback)
67  {
68  callback_ = callback;
69  }
70 
71  void stop()
72  {
73  // timer_.stop();
74  active_ = false;
75  }
76 
77  const ros::Timer & operator=(const ros::Timer & rhs)
78  {
79  active_ = true;
80  timer_ = rhs;
81  return timer_;
82  }
83 
84 private:
86  bool active_;
87  boost::function<void(const ros::TimerEvent & e)> callback_;
88 };
89 
90 
91 #endif // ACTIONLIB__ONE_SHOT_TIMER_H_
ros::Timer timer_
boost::function< void(const ros::TimerEvent &e)> getCb()
void cb(const ros::TimerEvent &e)
const ros::Timer & operator=(const ros::Timer &rhs)
boost::function< void(const ros::TimerEvent &e)> callback_
Horrible hack until ROS Supports this (ROS Trac #1387)
#define ROS_ERROR_NAMED(name,...)
void registerOneShotCb(boost::function< void(const ros::TimerEvent &e)> callback)


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 18 2019 03:59:59