Skip to content

Commit

Permalink
Sub: Don't send battery percent remaining estimate
Browse files Browse the repository at this point in the history
  • Loading branch information
jaxxzer committed May 4, 2017
1 parent 422c10c commit 5d5611c
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,8 @@ NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
int8_t battery_remaining = -1;

if (battery.has_current() && battery.healthy()) {
battery_remaining = battery.capacity_remaining_pct();
// percent remaining is not necessarily accurate at the moment
//battery_remaining = battery.capacity_remaining_pct();
battery_current = battery.current_amps() * 100;
}

Expand Down

0 comments on commit 5d5611c

Please sign in to comment.