|
From: <wg_...@us...> - 2009-08-24 22:36:39
|
Revision: 22772
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=22772&view=rev
Author: wg_cmeyers
Date: 2009-08-24 22:36:30 +0000 (Mon, 24 Aug 2009)
Log Message:
-----------
Added relative_capacity to the PowerState message, this is your
basic fuel guage 0-100%
Modified Paths:
--------------
pkg/trunk/stacks/pr2_common/pr2_msgs/msg/PowerState.msg
pkg/trunk/stacks/pr2_power_drivers/power_monitor/src/power_monitor.cpp
Modified: pkg/trunk/stacks/pr2_common/pr2_msgs/msg/PowerState.msg
===================================================================
--- pkg/trunk/stacks/pr2_common/pr2_msgs/msg/PowerState.msg 2009-08-24 22:31:56 UTC (rev 22771)
+++ pkg/trunk/stacks/pr2_common/pr2_msgs/msg/PowerState.msg 2009-08-24 22:36:30 UTC (rev 22772)
@@ -2,4 +2,5 @@
float64 power_consumption ## Watts
int64 time_remaining ## minutes
string prediction_method ## how time_remaining is being calculated
+int8 relative_capacity ## percent of capacity
int8 AC_present ## number of packs detecting AC power
Modified: pkg/trunk/stacks/pr2_power_drivers/power_monitor/src/power_monitor.cpp
===================================================================
--- pkg/trunk/stacks/pr2_power_drivers/power_monitor/src/power_monitor.cpp 2009-08-24 22:31:56 UTC (rev 22771)
+++ pkg/trunk/stacks/pr2_power_drivers/power_monitor/src/power_monitor.cpp 2009-08-24 22:36:30 UTC (rev 22772)
@@ -36,7 +36,9 @@
int acCount(0);
//float totalCurrent[batteryServers.size()];
float totalPower(0.0);
- unsigned int minTime(65535);
+ unsigned int minTime(65535); //for discharging
+ unsigned int maxTime(0); //for charging
+ int minCapacity(1000);
boost::mutex::scoped_lock lock(vLock);
map< int, boost::shared_ptr<pr2_msgs::BatteryServer const> >::iterator itr = batteryServers.begin();
@@ -64,8 +66,16 @@
totalPower += (current * voltage);
unsigned tte = bat->battery[xx].batReg[0x12];
- if(tte < minTime) //search for battery is least time remaining
+ if(tte < minTime) //search for battery with least time remaining
minTime = tte;
+
+ unsigned ttf = bat->battery[xx].batReg[0x13];
+ if(ttf > maxTime) //search for battery with longtest recharge time
+ maxTime = ttf;
+
+ unsigned rsc = bat->battery[xx].batReg[0x0d];
+ if(rsc < minCapacity) //search for battery with lowest state of charge
+ minCapacity = rsc;
}
//totalCurrent[bat->id] = tmpCurrent;
@@ -75,9 +85,13 @@
ROS_DEBUG(" totalPower=%f", totalPower);
powerState.power_consumption = totalPower;
- powerState.time_remaining = minTime;
+ powerState.AC_present = acCount;
+ if(acCount > 0) //Are we charging??
+ powerState.time_remaining = maxTime;
+ else
+ powerState.time_remaining = minTime;
powerState.prediction_method = "fuel guage";
- powerState.AC_present = acCount;
+ powerState.relative_capacity = minCapacity;
pub.publish(powerState);
};
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|