mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: use should_log() for more msgs
This commit is contained in:
parent
3d167b5420
commit
ce3f40b095
@ -1046,7 +1046,7 @@ static void update_GPS_50Hz(void)
|
||||
g_gps2->update();
|
||||
if (g_gps2->last_message_time_ms() != last_gps2_reading) {
|
||||
last_gps2_reading = g_gps2->last_message_time_ms();
|
||||
if (g.log_bitmask & MASK_LOG_GPS) {
|
||||
if (should_log(MASK_LOG_GPS)) {
|
||||
DataFlash.Log_Write_GPS2(g_gps2);
|
||||
}
|
||||
}
|
||||
|
@ -24,7 +24,7 @@ static bool
|
||||
start_command(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
// log when new commands start
|
||||
if (g.log_bitmask & MASK_LOG_CMD) {
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
Log_Write_Cmd(cmd);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user