AP_Vehicle: output rcout banner when initialization is done

move down ready message
This commit is contained in:
Andy Piper 2021-08-11 15:23:26 +01:00 committed by Randy Mackay
parent 761fc57a18
commit c6247433df
1 changed files with 7 additions and 2 deletions

View File

@ -139,7 +139,6 @@ void AP_Vehicle::setup()
// init_ardupilot is where the vehicle does most of its initialisation.
init_ardupilot();
gcs().send_text(MAV_SEVERITY_INFO, "ArduPilot Ready");
#if !APM_BUILD_TYPE(APM_BUILD_Replay)
SRV_Channels::init();
@ -175,7 +174,7 @@ void AP_Vehicle::setup()
#if GENERATOR_ENABLED
generator.init();
#endif
gcs().send_text(MAV_SEVERITY_INFO, "ArduPilot Ready");
}
void AP_Vehicle::loop()
@ -193,6 +192,12 @@ void AP_Vehicle::loop()
*/
done_safety_init = true;
BoardConfig.init_safety();
// send RC output mode info if available
char banner_msg[50];
if (hal.rcout->get_output_mode_banner(banner_msg, sizeof(banner_msg))) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", banner_msg);
}
}
}