power_state_estimator.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #ifndef POWER_MONITOR_POWER_STATE_ESTIMATOR_H
00036 #define POWER_MONITOR_POWER_STATE_ESTIMATOR_H
00037 
00038 #include <stdlib.h>
00039 
00040 #include "ros/ros.h"
00041 
00042 #include "observation.h"
00043 
00044 namespace power_monitor {
00045 
00046 struct PowerStateEstimate
00047 {
00048     ros::Duration time_remaining;
00049     unsigned int  relative_capacity;
00050 };
00051 
00055 class PowerStateEstimator
00056 {
00057 public:
00058     enum Type { FuelGauge, Advanced };
00059 
00060     PowerStateEstimator();
00061 
00062     virtual std::string               getMethodName() const = 0;
00063     virtual PowerStateEstimator::Type getMethodType() const = 0;
00064     virtual PowerStateEstimate        estimate(const ros::Time& t) = 0;
00065 
00066     virtual void recordObservation(const PowerObservation& obs);
00067 
00068     virtual bool canEstimate(const ros::Time& t) const;
00069 
00070 protected:
00071     PowerObservation obs_;
00072 };
00073 
00077 class FuelGaugePowerStateEstimator : public PowerStateEstimator
00078 {
00079 public:
00080     std::string               getMethodName() const;
00081     PowerStateEstimator::Type getMethodType() const;
00082     PowerStateEstimate        estimate(const ros::Time& t);
00083 };
00084 
00087 class AdvancedPowerStateEstimator : public PowerStateEstimator
00088 {
00089 public:
00090     struct LogRecord
00091     {
00092         uint32_t     sec;
00093         int8_t       master_state;
00094         int          charging;
00095         float        total_power;
00096         float        min_voltage;
00097         unsigned int min_relative_state_of_charge;
00098         float        total_remaining_capacity;
00099     };
00100 
00101     AdvancedPowerStateEstimator();
00102 
00103     std::string               getMethodName() const;
00104     PowerStateEstimator::Type getMethodType() const;
00105     PowerStateEstimate        estimate(const ros::Time& t);
00106 
00107     virtual void recordObservation(const PowerObservation& obs);
00108 
00109 private:
00110     static const std::string DEFAULT_LOG_FILE;
00111 
00112     static void tokenize(const std::string& str, std::vector<std::string>& tokens, const std::string& delimiters=",");
00113 
00114     bool readObservations(std::vector<LogRecord>& log);
00115     bool saveObservation(const PowerObservation& obs) const;
00116     bool hasEverDischarged() const;
00117 
00118     std::vector<LogRecord> log_;
00119 
00120     std::string log_filename_;
00121 };
00122 
00123 }
00124 
00125 #endif /* POWER_MONITOR_POWER_STATE_ESTIMATOR_H */


power_monitor
Author(s): Tim Field, Curt Meyers
autogenerated on Tue Apr 22 2014 19:35:04