When the system developers incorporate the changes to the software release, Power efficiency in watts/distance could be displayed and if the battery capacity is entered, "est. time remaining" could be available.
I used the AttoPilot 90A/50V Voltage/Current Sensor with Connectors
AttoPilot Voltage/Current Sensor with connectors
The sensor is also available from SparkFun http://www.sparkfun.com/products/9028
SparkFun Power sensor board (Same as AttoPilot board)
The sensor provides a scaled output for battery voltage and current. The outputs are scaled for a 12 bit 3.3V ADC. Full range is 51.8 Volts and 89.4 Amps.
The connector that is wired into the AttoPilot sensor is pinned for a direct connection to the APM shield.
To prep the shield I left the first two resistor positions open (no resistors installed) and shorted the last two positions.
I installed a 3 pin header. The 4th pin from the bottom of the row is ground (the black lead). The next pin up is battery voltage (the red lead). The 3rd pin is the battery current (white lead).
I noticed that during the "test -> battery" only 1 reading was displayed and it was inaccurate.
I changed the 'sensors' file so that the battery read continues until you hit Enter to exit.
To incorporate the Power Sensor I had to modify these files:
sensors
defines.h
test
config.h
APM_Config.h
ArduPilotMega
Here are the changes I made:
sensors
#if POWER_SENSOR == 1
void read_battery(void)
{
battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9; //reads power sensor voltage pin
battery_voltage2 = BATTERY_CURRENT(analogRead(BATTERY_PIN2)) * .1 + battery_voltage2 * .9; //reads power sensor current pin
battery_current = battery_voltage2;
}
#endif
#if BATTERY_EVENT == 1
void read_battery(void)
{
battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9;
battery_voltage2 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN2)) * .1 + battery_voltage2 * .9;
battery_voltage3 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN3)) * .1 + battery_voltage3 * .9;
battery_voltage4 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN4)) * .1 + battery_voltage4 * .9;
#if BATTERY_TYPE == 0
if(battery_voltage3 < LOW_VOLTAGE)
low_battery_event();
battery_voltage = battery_voltage3; // set total battery voltage, for telemetry stream
#endif
#if BATTERY_TYPE == 1
if(battery_voltage4 < LOW_VOLTAGE)
low_battery_event();
battery_voltage = battery_voltage4; // set total battery voltage, for telemetry stream
#endif
}
#endif
defines.h
#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO
#define BATTERY_CURRANT(x) (x*(INPUT_VOLTAGE/1024.0))*CURR_DIV_RATIO
test
static int8_t
test_battery(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
#if POWER_SENSOR == 1
while(1){
for (int i = 0; i < 20; i++){
delay(20);
read_battery();
}
Serial.printf_P(PSTR("Volts:"));
Serial.print(battery_voltage1, 2); //power sensor voltage pin
Serial.print(" Amps:");
Serial.println(battery_voltage2, 2); //power sensor current pin
if(Serial.available() > 0){
return (0);
}
}
#else
Serial.printf_P(PSTR("Power Sensor Not enabled\n"));
#endif
delay(3000);
#if BATTERY_EVENT == 1
while(1){
for (int i = 0; i < 20; i++){
delay(20);
read_battery();
}
Serial.printf_P(PSTR("Volts: 1:"));
Serial.print(battery_voltage1, 4);
Serial.print(" 2:");
Serial.print(battery_voltage2, 4);
Serial.print(" 3:");
Serial.print(battery_voltage3, 4);
Serial.print(" 4:");
Serial.println(battery_voltage4, 4);
if(Serial.available() > 0){
return (0);
}
}
#else
Serial.printf_P(PSTR("Battery Event Not enabled\n"));
#endif
delay(3000);
}
config.h
//////////////////////////////////////////////////////////////////////////////
// Battery monitoring
//
#ifndef POWER_SENSOR
# define POWER_SENSOR DISABLED
#endif
#ifndef BATTERY_EVENT
# define BATTERY_EVENT DISABLED
#endif
#ifndef BATTERY_TYPE
# define BATTERY_TYPE 0
#endif
#ifndef LOW_VOLTAGE
# define LOW_VOLTAGE 11.4
#endif
#ifndef VOLT_DIV_RATIO
# define VOLT_DIV_RATIO 3.0
#endif
#ifndef CURR_DIV_RATIO
# define CURR_DIV_RATIO 3.0
#endif
APM_Config.h
// Battery monitoring
#define POWER_SENSOR ENABLED
#define BATTERY_EVENT DISABLED
#define BATTERY_TYPE 0
#define LOW_VOLTAGE 9.6
#define VOLT_DIVRATIO 15.7 //AttoPilot sensor voltage ratio (Minor adjustments to these values
#define CURR_DIV_RATIO 30.35 //AttoPilot sensor current ratio allow calibration to desired accuracy)
ArduPilotMega
// Sensors
// --------
float airpressure_raw; // Airspeed Sensor - is a float to better handle filtering
int airpressure_offset; // analog air pressure sensor while still
int airpressure; // airspeed as a pressure value
float battery_voltage = LOW_VOLTAGE * 1.05; // Battery Voltage of total battery, initialized above threshold for filter
float battery_voltage1 = LOW_VOLTAGE * 1.05; // Battery Voltage of cell 1, initialized above threshold for filter
float battery_voltage2 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2, initialized above threshold for filter
float battery_voltage3 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2+3, initialized above threshold for filter
float battery_voltage4 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1+2+3+4, initialized above threshold for filter
float battery_current;
Comments
I. I have been tempering with the attopilot current sensor and I have it showing both current and voltage on the APM, however I have a strange behaviour. I had to multiply by4 the reading from BATTERY_PIN1. I measured voltage on the 3 pin from the sensor and it showed 0.72 (for a 11.4V battery charge). So, if I divided the g.input_voltage/1024, believing g.input_voltage is 5V, I would have 0.00488V per unit, accordinglly with 0.72V, I should be reading about 147 / 148 units (0.72 / 0.00488). I was having readings of about 1/4 of the voltage, so I changed the code to show me the readings from BATTERY_PIN1 (analogRead(BATTERY_PIN1)) and it shows values of 36 / 37, wich is about 1/4 of what should be reading. I solved it by multiplying by 4, but now I don't know if I should multiply the current pin also (BATTERY_PIN2), but there should be an explanation. One I can think of, is that it's using only 8 bit resolution instead of 10, so if had (g.input_voltage/256) would solve it also, but don't know why is doing this. Does anyone have an explanation or has it happened to anyone else ?
If you add this to the APM_Config file: (after setting the bat. option to 4 and the capacity as needed)
#define VOLT_DIV_RATIO 16
the voltage indication will be very close.
Hi Marc. took the resistors out, used the APM setup in Mission Planner and set it to option 4 (monitor both current and voltage), and set capacity to 5000 (for the mAh of the battery I'm using). It's now reporting just 2.88 Volts. If I bridge AN0 it drops to .2 volts or something silly. I guess I have to learn how to compile with Arduino and modify the code then eh?
If you use AN4 / AN5 remember to put a ~10k ohm resistor or you will burn the input pin of the atmega.
Check this out: http://code.google.com/p/ardupilot-mega/wiki/Voltage it will help you. If you don't want to modify the code take the resistors out.
Yeah, I'm a noob who's mainly using just the Mission Planner to setup the out of the box Beta code. I'll have to wait I guess! thanks though Marc
If you want to measure voltages up to VCC you can use AN4 / AN5 they don't have a voltage divider (they are direct inputs to the atmega) but you will have to modify the code.
I installed this yesterday, but noticed my first two positions are already occupied by resistors, from the factory. Do I simply take these out, and solder the last two with links? thanks to all in advance!
Irvin,
I've been thinking about the wrong readings with no seonsor and came to the conclusion that the only solution is probably to use a pull-down resitor on the APM. Now, the problem is that, the gain of the sensor is determined by a pull-down resitor on the sensor's board and by adding another resitor to the APM the gain is reduced dramatically. Considering that the sensor was designed to deliver 3.3 V and the APM can digitize 5 V, we are already missing resolution and reducing gain further is no true option.
One possible modification would be to use a 220 kOhm pull-down on the APM and to exchange the 73.2 kOhm on the current sensor by 220 kOhm. Both together would correspond to 110 kOhm and should deliver 4.95 V output for 90 A. This way readings without a sensor connected would be fine and the resolution would be ideal for the APM. The only problem is that the gain of the the sensor alone would be half...
One thing I've observed in the last days was that, the sensor delivers about 0.525 A for small loads (like a couple of mA). This is also the case when you measure the voltage at the sensor without connecting it to the APM. The sensor consumes only about 0,8 mA, which cannot explain this value. I measured the current for loads of about 60 to 300 mA and it seems to me that it is a systematic error (compare datasheet of INA169). Here is one log exemplifying the behaviour:
At the beginning of the log no sensor was connected. Remark: the sensor was present during boot-up, therefore 0 A are shown and not 35 A. After connecting the sensor the current jumps to 0,525 A. I connected then a 60 mA load and later an additional one with 300 mA. Ignoring the offset of 0.525 A, the readings seem to be fine for small loads too. Can you confirm this behaviour? I use a scaling of 27.3182 A/V in the software.
@Tom: In principle any sensor with a linear characteristic and an output range of 0 to 5 V should work. If everything goes well, the user has only to change the value of the scaling factor in APM_Config.h.
Regards,
Andrés