mirror of https://github.com/ArduPilot/ardupilot
Rover: use should_log() for more log msgs
This commit is contained in:
parent
abfcee1cef
commit
3d167b5420
|
@ -824,7 +824,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);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -14,6 +14,11 @@ static bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
|
|||
static bool
|
||||
start_command(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
// log when new commands start
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
Log_Write_Cmd(cmd);
|
||||
}
|
||||
|
||||
// exit immediately if not in AUTO mode
|
||||
if (control_mode != AUTO) {
|
||||
return false;
|
||||
|
|
|
@ -233,8 +233,9 @@ static void init_ardupilot()
|
|||
|
||||
startup_ground();
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_CMD)
|
||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||
if (should_log(MASK_LOG_CMD)) {
|
||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||
}
|
||||
|
||||
set_mode((enum mode)g.initial_mode.get());
|
||||
|
||||
|
@ -328,8 +329,9 @@ static void set_mode(enum mode mode)
|
|||
break;
|
||||
}
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_MODE)
|
||||
if (should_log(MASK_LOG_MODE)) {
|
||||
Log_Write_Mode();
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue