time_util.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
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 }


jsk_recognition_utils
Author(s):
autogenerated on Sun Oct 8 2017 02:42:48