Browse Source

Plane: batt curr and remaining should be int16

master
Randy Mackay 12 years ago
parent
commit
9722276827
  1. 4
      ArduPlane/GCS_Mavlink.pde
  2. 4
      ArduPlane/sensors.pde

4
ArduPlane/GCS_Mavlink.pde

@ -213,8 +213,8 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack @@ -213,8 +213,8 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
control_sensors_health &= ~(1<<5); // GPS unhealthy
}
uint16_t battery_current = -1;
uint8_t battery_remaining = -1;
int16_t battery_current = -1;
int8_t battery_remaining = -1;
if (battery.monitoring() == AP_BATT_MONITOR_VOLTAGE_AND_CURRENT) {
battery_remaining = battery.capacity_remaining_pct();

4
ArduPlane/sensors.pde

@ -44,10 +44,6 @@ static void zero_airspeed(void) @@ -44,10 +44,6 @@ static void zero_airspeed(void)
// should be called at 10hz
static void read_battery(void)
{
if(battery.monitoring() == AP_BATT_MONITOR_DISABLED) {
return;
}
battery.read();
if (!usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {

Loading…
Cancel
Save