Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "jsk_recognition_utils/time_util.h"
00037 #include <std_msgs/Float32.h>
00038
00039 namespace jsk_recognition_utils
00040 {
00041 ScopedWallDurationReporter::ScopedWallDurationReporter(WallDurationTimer* parent):
00042 parent_(parent), start_time_(ros::WallTime::now()),
00043 is_publish_(false), is_enabled_(true)
00044 {
00045
00046 }
00047
00048 ScopedWallDurationReporter::ScopedWallDurationReporter(
00049 WallDurationTimer* parent,
00050 ros::Publisher& pub_latest,
00051 ros::Publisher& pub_average):
00052 parent_(parent), start_time_(ros::WallTime::now()),
00053 pub_latest_(pub_latest), pub_average_(pub_average),
00054 is_publish_(true), is_enabled_(true)
00055 {
00056
00057 }
00058
00059 ScopedWallDurationReporter::~ScopedWallDurationReporter()
00060 {
00061 ros::WallTime end_time = ros::WallTime::now();
00062 ros::WallDuration d = end_time - start_time_;
00063 if (is_enabled_) {
00064 parent_->report(d);
00065 if (is_publish_) {
00066 std_msgs::Float32 ros_latest;
00067 ros_latest.data = parent_->latestSec();
00068 pub_latest_.publish(ros_latest);
00069 std_msgs::Float32 ros_average;
00070 ros_average.data = parent_->meanSec();
00071 pub_average_.publish(ros_average);
00072 }
00073 }
00074 }
00075
00076 void ScopedWallDurationReporter::setIsPublish(bool v)
00077 {
00078 is_publish_ = v;
00079 }
00080
00081 void ScopedWallDurationReporter::setIsEnabled(bool v)
00082 {
00083 is_enabled_ = v;
00084 }
00085
00086 WallDurationTimer::WallDurationTimer(const int max_num):
00087 max_num_(max_num), buffer_(max_num)
00088 {
00089 }
00090
00091 void WallDurationTimer::report(ros::WallDuration& duration)
00092 {
00093 buffer_.push_back(duration);
00094 }
00095
00096 ScopedWallDurationReporter WallDurationTimer::reporter()
00097 {
00098 return ScopedWallDurationReporter(this);
00099 }
00100
00101 ScopedWallDurationReporter WallDurationTimer::reporter(
00102 ros::Publisher& pub_latest,
00103 ros::Publisher& pub_average)
00104 {
00105 return ScopedWallDurationReporter(this, pub_latest, pub_average);
00106 }
00107
00108 double WallDurationTimer::latestSec()
00109 {
00110 return buffer_[buffer_.size() - 1].toSec();
00111 }
00112
00113 void WallDurationTimer::clearBuffer()
00114 {
00115 buffer_.clear();
00116 }
00117
00118 double WallDurationTimer::meanSec()
00119 {
00120 double secs = 0.0;
00121 for (size_t i = 0; i < buffer_.size(); i++) {
00122 secs += buffer_[i].toSec();
00123 }
00124 return secs / buffer_.size();
00125 }
00126
00127 size_t WallDurationTimer::sampleNum()
00128 {
00129 return buffer_.size();
00130 }
00131 }