timer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
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/timer.h"
29 #include "ros/timer_manager.h"
30 
31 namespace roswrap
32 {
33 
35  : started_(false)
36  , timer_handle_(-1)
37 { }
38 
40 {
41  ROS_DEBUG("Timer deregistering callbacks.");
42  stop();
43 }
44 
46 {
47  return !period_.isZero();
48 }
49 
51 {
52  if (!started_)
53  {
54  VoidConstPtr tracked_object;
55  if (has_tracked_object_)
56  {
57  tracked_object = tracked_object_.lock();
58  }
59 
60  timer_handle_ = TimerManager<Time, Duration, TimerEvent>::global().add(period_, callback_, callback_queue_, tracked_object, oneshot_);
61  started_ = true;
62  }
63 }
64 
66 {
67  if (started_)
68  {
69  started_ = false;
71  timer_handle_ = -1;
72  }
73 }
74 
76 {
77  if (!isValid() || timer_handle_ == -1)
78  {
79  return false;
80  }
81 
83 }
84 
85 void Timer::Impl::setPeriod(const Duration& period, bool reset)
86 {
87  period_ = period;
88  TimerManager<Time, Duration, TimerEvent>::global().setPeriod(timer_handle_, period, reset);
89 }
90 
92 : impl_(new Impl)
93 {
94  impl_->period_ = ops.period;
95  impl_->callback_ = ops.callback;
96  impl_->callback_queue_ = ops.callback_queue;
97  impl_->tracked_object_ = ops.tracked_object;
98  impl_->has_tracked_object_ = (ops.tracked_object != NULL);
99  impl_->oneshot_ = ops.oneshot;
100 }
101 
102 Timer::Timer(const Timer& rhs)
103 {
104  impl_ = rhs.impl_;
105 }
106 
108 {
109 }
110 
112 {
113  if (impl_)
114  {
115  impl_->start();
116  }
117 }
118 
120 {
121  if (impl_)
122  {
123  impl_->stop();
124  }
125 }
126 
128 {
129  if (impl_)
130  {
131  return impl_->hasPending();
132  }
133 
134  return false;
135 }
136 
137 void Timer::setPeriod(const Duration& period, bool reset)
138 {
139  if (impl_)
140  {
141  impl_->setPeriod(period, reset);
142  }
143 }
144 
145 }
roswrap::Timer::Impl::setPeriod
void setPeriod(const Duration &period, bool reset=true)
Definition: timer.cpp:85
roswrap::TimerOptions
Encapsulates all options available for starting a timer.
Definition: timer_options.h:41
roswrap::Timer::start
void start()
Start the timer. Does nothing if the timer is already started.
Definition: timer.cpp:111
roswrap::Timer::stop
void stop()
Stop the timer. Once this call returns, no more callbacks will be called. Does nothing if the timer i...
Definition: timer.cpp:119
roswrap::TimerManager::hasPending
bool hasPending(int32_t handle)
Definition: timer_manager.h:259
NULL
#define NULL
roswrap::Timer::~Timer
~Timer()
Definition: timer.cpp:107
roswrap::TimerManager::global
static TimerManager & global()
Definition: timer_manager.h:99
roswrap::TimerManager::remove
void remove(int32_t handle)
Definition: timer_manager.h:332
roswrap::Timer::Impl::isValid
bool isValid()
Definition: timer.cpp:45
roswrap::Timer::Impl
Definition: timer.h:96
roswrap::TimerOptions::oneshot
bool oneshot
Definition: timer_options.h:78
roswrap::Timer
Manages a timer callback.
Definition: timer.h:47
roswrap::Timer::Impl::stop
void stop()
Definition: timer.cpp:65
roswrap::TimerOptions::period
Duration period
The period to call the callback at.
Definition: timer_options.h:63
roswrap::TimerOptions::tracked_object
VoidConstPtr tracked_object
Definition: timer_options.h:76
roswrap::Duration
Duration representation for use with the Time class.
Definition: duration.h:109
roswrap::TimerManager::setPeriod
void setPeriod(int32_t handle, const D &period, bool reset=true)
Definition: timer_manager.h:423
roswrap::TimerManager::add
int32_t add(const D &period, const std::function< void(const E &)> &callback, CallbackQueueInterface *callback_queue, const VoidConstPtr &tracked_object, bool oneshot)
Definition: timer_manager.h:283
roswrap::Timer::Timer
Timer()
Definition: timer.h:50
roswrap
Definition: param_modi.cpp:41
roswrap::Timer::setPeriod
void setPeriod(const Duration &period, bool reset=true)
Set the period of this timer.
Definition: timer.cpp:137
roswrap::TimerOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: timer_options.h:66
roswrap::Timer::Impl::start
void start()
Definition: timer.cpp:50
roswrap::Timer::Impl::~Impl
~Impl()
Definition: timer.cpp:39
ROS_DEBUG
#define ROS_DEBUG(...)
Definition: sick_scan_logging.h:112
roswrap::Timer::Impl::hasPending
bool hasPending()
Definition: timer.cpp:75
roswrap::Timer::impl_
ImplPtr impl_
Definition: timer.h:122
roswrap::Timer::isValid
bool isValid()
Definition: timer.h:75
roswrap::Timer::hasPending
bool hasPending()
Returns whether or not the timer has any pending events to call.
Definition: timer.cpp:127
roswrap::VoidConstPtr
std::shared_ptr< void const > VoidConstPtr
Definition: forwards.h:54
roswrap::Timer::Impl::Impl
Impl()
Definition: timer.cpp:34
roswrap::TimerOptions::callback
TimerCallback callback
The callback to call.
Definition: timer_options.h:64


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:12