28 #ifndef ROSCPP_TIMER_H 29 #define ROSCPP_TIMER_H 52 Timer& operator=(
const Timer& other) =
default;
73 void setPeriod(
const Duration& period,
bool reset=
true);
75 bool hasStarted()
const {
return impl_ && impl_->hasStarted(); }
76 bool isValid() {
return impl_ && impl_->isValid(); }
77 bool isValid()
const {
return impl_ && impl_->isValid(); }
78 operator void*() {
return isValid() ? (
void*)1 : (
void*)0; }
82 return impl_ < rhs.
impl_;
87 return impl_ == rhs.
impl_;
92 return impl_ != rhs.
impl_;
104 bool hasStarted()
const;
106 bool isValid()
const;
108 void setPeriod(
const Duration& period,
bool reset=
true);
bool operator<(const Timer &rhs)
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
boost::function< void(const TimerEvent &)> TimerCallback
VoidConstWPtr tracked_object_
Abstract interface for a queue used to handle all callbacks within roscpp.
boost::shared_ptr< Impl > ImplPtr
bool operator!=(const Timer &rhs)
bool operator==(const Timer &rhs)
boost::weak_ptr< void const > VoidConstWPtr
roscpp's interface for creating subscribers, publishers, etc.
Encapsulates all options available for starting a timer.
Manages a timer callback.
CallbackQueueInterface * callback_queue_
boost::weak_ptr< Impl > ImplWPtr