Arducoper ACM?
What steps will reproduce the problem?
1. Always there
What is the expected output? What do you see instead?
mavlink_sys_status should report "battery remaining" to be able to see
remaining Power in GCS.
This is already corrected in APM trunk and needs to be synced to ACM.
http://code.google.com/p/ardupilot-mega/source/browse/ArduPilotMega/trunk/Mavlin
k_Common.h
What version of the product are you using? On what operating system?
2.0.20
Please provide any additional information below.
Index: ArduCopterMega/Mavlink_Common.h
===================================================================
--- ArduCopterMega/Mavlink_Common.h (revision 2450)
+++ ArduCopterMega/Mavlink_Common.h (working copy)
@@ -70,9 +70,8 @@
}
uint8_t status = MAV_STATE_ACTIVE;
- uint16_t battery_remaining = 10.0 * (float)(g.pack_capacity -
current_total)/g.pack_capacity; //Mavlink scaling 100% = 1000
+ uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity -
current_total)/g.pack_capacity; //Mavlink scaling 100% = 1000
uint8_t motor_block = false;
-
mavlink_msg_sys_status_send(
chan,
mode,
@@ -80,7 +79,7 @@
status,
load * 1000,
battery_voltage * 1000,
- motor_block,
+ battery_remaining,
packet_drops);
break;
}
Original issue reported on code.google.com by fueck...@gmail.com on 1 Jun 2011 at 1:08
Original issue reported on code.google.com by
fueck...@gmail.com
on 1 Jun 2011 at 1:08