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 #include "power_monitor.h"
00036
00037 using namespace std;
00038 using namespace power_monitor;
00039
00040 PowerMonitor::PowerMonitor() : master_state_(-1)
00041 {
00042 ros::NodeHandle node;
00043
00044 string battery_server_topic = "battery/server2";
00045 string power_board_node = "power_board";
00046 string estimator_type_str = "advanced";
00047 double freq = 0.1;
00048
00049 node.getParam("battery_server_topic", battery_server_topic);
00050 node.getParam("power_board_node", power_board_node);
00051 node.getParam("estimation_method", estimator_type_str);
00052 node.getParam("frequency", freq);
00053
00054 ros::Duration(2).sleep();
00055
00056
00057 addEstimator(new FuelGaugePowerStateEstimator());
00058 addEstimator(new AdvancedPowerStateEstimator());
00059
00060
00061 dynamic_reconfigure::Server<PowerMonitorConfig>::CallbackType config_callback = boost::bind(&PowerMonitor::configCallback, this, _1, _2);
00062 config_server_.setCallback(config_callback);
00063
00064
00065 if (estimator_types_.size() == 0)
00066 {
00067 ROS_FATAL("No power state estimators defined. Shutting down");
00068 exit(1);
00069 }
00070 map<string, PowerStateEstimator::Type>::const_iterator i = estimator_types_.find(estimator_type_str);
00071 if (i == estimator_types_.end())
00072 {
00073
00074 string first_estimator_type_str = estimator_types_.begin()->first;
00075 ROS_ERROR("Unknown power state estimator type: %s. Defaulting to %s", estimator_type_str.c_str(), first_estimator_type_str.c_str());
00076 setActiveEstimator(estimator_types_.begin()->second);
00077 }
00078 else
00079 setActiveEstimator(i->second);
00080
00081 power_state_pub_ = node.advertise<pr2_msgs::PowerState>("power_state", 5, true);
00082 power_state_pub_timer_ = node.createTimer(ros::Duration(1.0 / freq), &PowerMonitor::onPublishTimer, this);
00083 battery_server_sub_ = node.subscribe(battery_server_topic, 10, &PowerMonitor::batteryServerUpdate, this);
00084 power_node_sub_ = node.subscribe(node.resolveName(power_board_node) + "/state", 10, &PowerMonitor::powerNodeUpdate, this);
00085 }
00086
00087 void PowerMonitor::addEstimator(PowerStateEstimator* est)
00088 {
00089 estimator_types_[est->getMethodName()] = est->getMethodType();
00090 estimators_[est->getMethodType()] = boost::shared_ptr<PowerStateEstimator>(est);
00091 }
00092
00093 void PowerMonitor::configCallback(PowerMonitorConfig& config, uint32_t level)
00094 {
00095 setActiveEstimator((PowerStateEstimator::Type) config.power_state_estimator_);
00096 }
00097
00098 bool PowerMonitor::setActiveEstimator(PowerStateEstimator::Type estimator_type)
00099 {
00100 map<PowerStateEstimator::Type, boost::shared_ptr<PowerStateEstimator> >::const_iterator i = estimators_.find(estimator_type);
00101 if (i == estimators_.end())
00102 return false;
00103 if (active_estimator_ == i->second)
00104 return true;
00105
00106 if (active_estimator_ == boost::shared_ptr<PowerStateEstimator>())
00107 ROS_INFO("Power state estimator set to %s", i->second->getMethodName().c_str());
00108 else
00109 ROS_INFO("Power state estimator changed from %s to %s", active_estimator_->getMethodName().c_str(), i->second->getMethodName().c_str());
00110
00111 active_estimator_ = i->second;
00112
00113 return true;
00114 }
00115
00116 void PowerMonitor::batteryServerUpdate(const boost::shared_ptr<const pr2_msgs::BatteryServer2>& battery_server)
00117 {
00118 boost::mutex::scoped_lock lock(update_mutex_);
00119
00120 ROS_DEBUG("Received battery message: voltage=%.2f", battery_server->battery[0].battery_register[0x9] / 1000.0f);
00121
00122 battery_servers_[battery_server->id] = battery_server;
00123 }
00124
00125 void PowerMonitor::powerNodeUpdate(const boost::shared_ptr<const pr2_msgs::PowerBoardState>& power_board_state)
00126 {
00127 boost::mutex::scoped_lock lock(update_mutex_);
00128
00129 ROS_DEBUG("Received power board state message: %s", masterStateToString(power_board_state->master_state).c_str());
00130
00131 master_state_ = power_board_state->master_state;
00132
00133
00134 if (master_state_ == pr2_msgs::PowerBoardState::MASTER_SHUTDOWN)
00135 publishPowerState();
00136 }
00137
00138 string PowerMonitor::masterStateToString(int8_t master_state) const
00139 {
00140 switch (master_state)
00141 {
00142 case pr2_msgs::PowerBoardState::MASTER_NOPOWER: return "No Power";
00143 case pr2_msgs::PowerBoardState::MASTER_STANDBY: return "Standby";
00144 case pr2_msgs::PowerBoardState::MASTER_ON: return "On";
00145 case pr2_msgs::PowerBoardState::MASTER_OFF: return "Off";
00146 case pr2_msgs::PowerBoardState::MASTER_SHUTDOWN: return "Shutdown";
00147 default: return "Unknown";
00148 }
00149 }
00150
00151 PowerObservation PowerMonitor::extractObservation()
00152 {
00153 boost::mutex::scoped_lock lock(update_mutex_);
00154
00155 vector<BatteryObservation> batteries;
00156 for (map<int, boost::shared_ptr<const pr2_msgs::BatteryServer2> >::iterator i = battery_servers_.begin(); i != battery_servers_.end(); i++)
00157 {
00158 const pr2_msgs::BatteryServer2* bs = i->second.get();
00159
00160 ros::Time stamp = bs->header.stamp;
00161
00162 for (unsigned int j = 0; j < bs->battery.size(); j++)
00163 {
00164 const pr2_msgs::BatteryState2& b = bs->battery[j];
00165
00166 bool ac_present = b.power_present;
00167 float voltage = b.battery_register[0x9] / 1000.0f;
00168 float current = b.battery_register[0xA] / 1000.0f;
00169 unsigned int rsc = b.battery_register[0x0D];
00170 float rem_cap = b.battery_register[0x0F] / 1000.0f;
00171 unsigned int tte_min = b.battery_register[0x12];
00172 unsigned int ttf_min = b.battery_register[0x13];
00173
00174 ros::Duration tte;
00175 if (tte_min > 0)
00176 tte = ros::Duration(tte_min * 60, 0);
00177 else
00178 tte = ros::Duration(-1, 0);
00179
00180 ros::Duration ttf;
00181 if (ttf_min > 0)
00182 ttf = ros::Duration(ttf_min * 60, 0);
00183 else
00184 ttf = ros::Duration(-1, 0);
00185
00186 if (voltage == 0.0)
00187 continue;
00188
00189 batteries.push_back(BatteryObservation(stamp, ac_present, voltage, current, rsc, rem_cap, tte, ttf));
00190
00191 ROS_DEBUG("Battery %d.%d: %6.2f V %6.2f A %6.2f W (soc: %d, cap: %6.2f, tte: %dm, ttf: %dm)", bs->id, j + 1, voltage, current, current * voltage, rsc, rem_cap, tte_min, ttf_min);
00192 }
00193 }
00194
00195 return PowerObservation(ros::Time::now(), master_state_, batteries);
00196 }
00197
00198 void PowerMonitor::onPublishTimer(const ros::TimerEvent& e)
00199 {
00200 publishPowerState();
00201 }
00202
00203 void PowerMonitor::publishPowerState()
00204 {
00205 boost::mutex::scoped_lock lock(publish_mutex_);
00206
00207
00208 PowerObservation obs = extractObservation();
00209 if (obs.getBatteries().size() == 0)
00210 {
00211 ROS_DEBUG("Nothing observed");
00212 return;
00213 }
00214
00215 ROS_DEBUG("Power: %6.1f W. Min voltage: %6.2f V", obs.getTotalPower(), obs.getMinVoltage());
00216
00217
00218 for (map<PowerStateEstimator::Type, boost::shared_ptr<PowerStateEstimator> >::const_iterator i = estimators_.begin(); i != estimators_.end(); i++)
00219 i->second.get()->recordObservation(obs);
00220
00221
00222 ros::Time t = ros::Time::now();
00223 if (active_estimator_->canEstimate(t))
00224 {
00225 PowerStateEstimate estimate = active_estimator_->estimate(t);
00226 ROS_DEBUG("Remaining: %.0f min (%d%%)", estimate.time_remaining.toSec() / 60, estimate.relative_capacity);
00227
00228
00229 pr2_msgs::PowerState ps;
00230 ps.header.stamp = ros::Time::now();
00231 ps.AC_present = obs.getAcCount();
00232 ps.power_consumption = obs.getTotalPower();
00233 ps.prediction_method = active_estimator_->getMethodName();
00234 ps.relative_capacity = (int8_t) estimate.relative_capacity;
00235 ps.time_remaining = estimate.time_remaining;
00236 power_state_pub_.publish(ps);
00237 }
00238 }
00239
00240 int main(int argc, char** argv)
00241 {
00242 ros::init(argc, argv, "power_monitor");
00243 PowerMonitor monitor;
00244 ros::spin();
00245 return 0;
00246 }