jaspreeth / ardupilot-mega

Automatically exported from code.google.com/p/ardupilot-mega
0 stars 0 forks source link

Battery current/mAh monitoring #298

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
What steps will reproduce the problem?
1.Any usage of "current_total" variable from routine read_current in 
sensors.pde   

What is the expected output? What do you see instead?
Variable "current_total" should track the integrated current value to indicate 
battery usage.

What version of the product are you using? On what operating system?
APM 2.0 (same code in 2.01), using XP

Please provide any additional information below.

The routine in read_current() in sensors.pde includes the following line:
current_total += (current_amps * 0.27777) / delta_ms_medium_loop;

Two issues:
1. The "current_amps" variable should be multiplied by the delta time value 
rather than divided by it.
2. The variable "delta_ms_medium_loop" is set to the same value as 
"delta_ms_fast_loop" in routine loop() in module ArdPilotMega.pde whereas is 
should be a factor of 5 higher (nominally 100ms vs. 20ms) due to the five 
sub-banded sections in the medium loop. There is a comment on the line that 
indicates this is a temporary situation.

Based on "current_amps" being scaled in Amps, and "current_total" being scaled 
in mAh, the equation should read:
current_total += (current_amps * (float)delta_ms_fast_loop * 5 * 0.000278);     
Then, once "delta_ms_medium_loop: is properly set, the equation should read:
current_total += (current_amps * (float)delta_ms_medium_loop * 0.000278);       

Also, some current sensors have an offset output to allow for sensing of 
positive and negative current flow. It would be helpful if the offset could be 
accommodated by changing the current computation as follows in defines.h:
#define CURRENT_AMPS(x) 
((x*(INPUT_VOLTAGE/1024.0))-CURR_AMP_OFFSET)*CURR_AMP_DIV_RATIO

CURR_AMP_OFFSET should be initialized by default to 0.0, with the user being 
able to change it in APM_config.h to a value such as 2.5 when 2.5 volts on the 
input indicates zero current.

Original issue reported on code.google.com by AndrewJF...@gmail.com on 24 Mar 2011 at 1:25

GoogleCodeExporter commented 8 years ago

Original comment by dewei...@gmail.com on 24 Mar 2011 at 5:08

GoogleCodeExporter commented 8 years ago
I have implemented significant changes in this area.  

First: battery monitoring is enabled, and the type of monitoring (eg cell 
voltages, total voltage only, or voltage and current) using the parameter 
g.battery_monitoring (BATT_MONITOR).  The value should be set to 0 to disable 
battery monitoring, 1 to measure cell voltages for a 3 cell lipo, 2 to measure 
cell voltages for a 4 cell lipo, 3 to measure the total battery voltage (only) 
on input 1, or 4 to measure total battery voltage on input 1 and current on 
input 2.  This can be set through the CLI or GCS.

Second:  I did away with the separate voltage divider parameter 
CURR_VOLT_DIV_RATIO and renamed CURR_AMP_DIV_RATION to CURR_AMP_PER_VOLT.  The 
voltage input should still be on input 1 (pin 0).  I would NOT recommend using 
the voltage divider on the Attopilot current board due to the resulting low 
resolution - use the APM divider instead.  The current input should be on input 
2 (pin 1), and no divider resistor should be installed on APM.  The default 
value of CURR_AMP_PER_VOLT has been set to correspond to the Attopilot board 
spec.

Third: I changed the implementation of BATTERY_EVENT so that it controls 
whether or not warnings are given, but not whether battery monitoring is 
performed.  Warnings can be generated on low voltage or high pack discharge, 
depending on the monitoring type.

Fourth: A current sensor offset was added as requested.

Fifth: The calculation of milliamp-hours capacity used has been corrected.

These changes are in r2612.  This compiles but is untested so far.  Please 
check it out.

Original comment by dewei...@gmail.com on 21 Apr 2011 at 3:51

GoogleCodeExporter commented 8 years ago
Thank you for the updates - the ability to select the monitoring modes should 
make it work for most people without code changes.

I downloaded the latest source code did some bench tests. I got it to work 
fine, but needed to do the following:

1. Routine read_battery in module sensors.pde has two calls to set 
"current_amps" and "current_total". The calls in the "g.battery_monitoring==4" 
section are fine, but the first set at the start of the routine should be 
removed.Doesn't really hurt the calculation of "current_amps" apart from 
speeding up the filter, but "current_total" will increment twice as fast as it 
should.

2. The #define for "CURRENT_AMPS(x)" in module define.h has 
"CURRENT_AMP_OFFSET", whereas other routines use "CURRENT_AMPS_OFFSET" (extra 
"S"). These need to be the same. I changed the definition of "CURRENT_AMPS(x)" 
so that "CURRENT_AMPS_OFFSET" becomes the standard.

3. The call to "mavlink_msg_sys_status_send" in mavlink_common.h references 
"battery_voltage1". Should be "battery_voltage".

4. I haven't worked much with the common GCS to see that I really understand 
how this is supposed to work, but the definition of the seventh parameter in 
mavlink_msg_sys_status_send is remaining battery contained in a uint16_t, with 
0=0% and 1000=100%, whereas the call in mavlink_common.h just sets it to 
"false". I changed it as shown below. Works fine on the code I have to drive 
the Remzibi OSD.

//  motor_block = false;

    uint16_t battery_remaining = (float)(HIGH_DISCHARGE - current_total)/HIGH_DISCHARGE*1000.0;     

    mavlink_msg_sys_status_send(
            chan,
            mode,
            nav_mode,
            status,
            load * 1000,
            battery_voltage * 1000,     //AJF - was battery_voltage1 * 1000
            battery_remaining,      //AJF - was motor_block
            packet_drops);

I haven't checked the low_battery_event.

Original comment by AndrewJF...@gmail.com on 23 Apr 2011 at 1:18

GoogleCodeExporter commented 8 years ago
Andrew,  thanks for the code review!  The SparkFun Autonomous Vehicle 
Competition is today.  Next week I will have time to make the changes you 
suggest.

Original comment by dewei...@gmail.com on 23 Apr 2011 at 1:08

GoogleCodeExporter commented 8 years ago
R2625 has the requested changes.  I also added in pack capacity (less reserve) 
as a parameter so that it can be changed without recompiling.  

Original comment by dewei...@gmail.com on 25 Apr 2011 at 9:49

GoogleCodeExporter commented 8 years ago
The battery monitoring in R2625 works fine for me. Thank you.

Andrew

Original comment by AndrewJF...@gmail.com on 26 Apr 2011 at 2:27

GoogleCodeExporter commented 8 years ago

Original comment by dewei...@gmail.com on 2 May 2011 at 12:33