steady_timer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017, Felix Ruess, Roboception GmbH
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #include "ros/steady_timer.h"
29 #include "ros/timer_manager.h"
30 
31 namespace ros
32 {
33 
35  : started_(false)
36  , timer_handle_(-1)
37 { }
38 
40 {
41  ROS_DEBUG("SteadyTimer deregistering callbacks.");
42  stop();
43 }
44 
46 {
47  return started_;
48 }
49 
51 {
52  if (!started_)
53  {
54  VoidConstPtr tracked_object;
56  {
57  tracked_object = tracked_object_.lock();
58  }
60  started_ = true;
61  }
62 }
63 
65 {
66  if (started_)
67  {
68  started_ = false;
70  timer_handle_ = -1;
71  }
72 }
73 
75 {
76  return !period_.isZero();
77 }
78 
80 {
81  if (!isValid() || timer_handle_ == -1)
82  {
83  return false;
84  }
85 
87 }
88 
89 void SteadyTimer::Impl::setPeriod(const WallDuration& period, bool reset)
90 {
91  period_ = period;
93 }
94 
95 
97 : impl_(new Impl)
98 {
99  impl_->period_ = ops.period;
100  impl_->callback_ = ops.callback;
101  impl_->callback_queue_ = ops.callback_queue;
102  impl_->tracked_object_ = ops.tracked_object;
103  impl_->has_tracked_object_ = (ops.tracked_object != NULL);
104  impl_->oneshot_ = ops.oneshot;
105 }
106 
108 {
109  impl_ = rhs.impl_;
110 }
111 
113 {
114 }
115 
117 {
118  if (impl_)
119  {
120  impl_->start();
121  }
122 }
123 
125 {
126  if (impl_)
127  {
128  impl_->stop();
129  }
130 }
131 
133 {
134  if (impl_)
135  {
136  return impl_->hasPending();
137  }
138 
139  return false;
140 }
141 
142 void SteadyTimer::setPeriod(const WallDuration& period, bool reset)
143 {
144  if (impl_)
145  {
146  impl_->setPeriod(period, reset);
147  }
148 }
149 
150 }
void start()
Start the timer. Does nothing if the timer is already started.
void remove(int32_t handle)
void stop()
Stop the timer. Once this call returns, no more callbacks will be called. Does nothing if the timer i...
VoidConstWPtr tracked_object_
Definition: steady_timer.h:117
SteadyTimerCallback callback
The callback to call.
WallDuration period
The period to call the callback at.
SteadyTimerCallback callback_
Definition: steady_timer.h:115
bool hasPending(int32_t handle)
void setPeriod(const WallDuration &period, bool reset=true)
Set the period of this timer.
int32_t add(const D &period, const boost::function< void(const E &)> &callback, CallbackQueueInterface *callback_queue, const VoidConstPtr &tracked_object, bool oneshot)
void setPeriod(const WallDuration &period, bool reset=true)
CallbackQueueInterface * callback_queue_
Definition: steady_timer.h:116
Manages a steady-clock timer callback.
Definition: steady_timer.h:46
bool hasPending()
Returns whether or not the timer has any pending events to call.
static TimerManager & global()
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Encapsulates all options available for starting a timer.
#define ROS_DEBUG(...)
void setPeriod(int32_t handle, const D &period, bool reset=true)


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:27