29 #ifndef SWRI_ROSCPP_H_ 30 #define SWRI_ROSCPP_H_ 61 total_periods_ += period;
67 min_period_ = std::min(min_period_, period);
68 max_period_ = std::max(max_period_, period);
71 tick_begin_normal_ = now;
78 total_durations_ += duration;
80 min_duration_ = duration;
81 max_duration_ = duration;
83 min_duration_ = std::min(min_duration_, duration);
84 max_duration_ = std::max(max_duration_, duration);
193 callback_ = callback;
205 (obj_->*callback_)(event);
210 #endif // SWRI_ROSCPP_H_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::WallDuration minDuration() const
ros::WallDuration maxDuration() const
ros::Duration meanPeriod() const
ros::WallDuration total_durations_
double meanFrequencyHz() const
void handleTimer(const ros::TimerEvent &event)
ros::Duration minPeriod() const
ros::WallDuration max_duration_
ros::Duration max_period_
ros::Duration desired_period_
ros::WallDuration min_duration_
ros::Duration total_periods_
ros::Duration desiredPeriod() const
ros::Time tick_begin_normal_
ROSTIME_DECL const Duration DURATION_MAX
TypedTimerImpl(ros::NodeHandle &nh, ros::Duration period, void(T::*callback)(const ros::TimerEvent &), T *obj)
ros::Duration min_period_
ros::WallTime tick_begin_wall_
ros::Duration maxPeriod() const
ros::WallDuration meanDuration() const