MAVLink app: send correct value when not estimating battery charge level

This commit is contained in:
Lorenz Meier
2015-04-25 09:45:16 +02:00
parent 75df06bc76
commit af22c49497
+2 -1
View File
@@ -539,7 +539,8 @@ protected:
msg.errors_count2 = status.errors_count2;
msg.errors_count3 = status.errors_count3;
msg.errors_count4 = status.errors_count4;
msg.battery_remaining = status.battery_remaining * 100.0f;
msg.battery_remaining = (msg.voltage_battery > 0) ?
status.battery_remaining * 100.0f : -1;
_mavlink->send_message(MAVLINK_MSG_ID_SYS_STATUS, &msg);
}