mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: log CURR message at 10hz
This commit is contained in:
parent
b0c9e97181
commit
fa9d10e59b
@ -1172,11 +1172,6 @@ static void one_hz_loop()
|
|||||||
Log_Write_Data(DATA_AP_STATE, ap.value);
|
Log_Write_Data(DATA_AP_STATE, ap.value);
|
||||||
}
|
}
|
||||||
|
|
||||||
// log battery info to the dataflash
|
|
||||||
if (g.log_bitmask & MASK_LOG_CURRENT) {
|
|
||||||
Log_Write_Current();
|
|
||||||
}
|
|
||||||
|
|
||||||
// perform pre-arm checks & display failures every 30 seconds
|
// perform pre-arm checks & display failures every 30 seconds
|
||||||
static uint8_t pre_arm_display_counter = 15;
|
static uint8_t pre_arm_display_counter = 15;
|
||||||
pre_arm_display_counter++;
|
pre_arm_display_counter++;
|
||||||
|
@ -118,6 +118,11 @@ static void read_battery(void)
|
|||||||
if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
if (!ap.usb_connected && !failsafe.battery && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
|
||||||
failsafe_battery_event();
|
failsafe_battery_event();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// log battery info to the dataflash
|
||||||
|
if (g.log_bitmask & MASK_LOG_CURRENT) {
|
||||||
|
Log_Write_Current();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// read the receiver RSSI as an 8 bit number for MAVLink
|
// read the receiver RSSI as an 8 bit number for MAVLink
|
||||||
|
Loading…
Reference in New Issue
Block a user