Plane: Quadplane: use get_frame_and_type_string

This commit is contained in:
Iampete1 2022-01-01 15:47:15 +00:00 committed by Andrew Tridgell
parent 7aca392dad
commit ca1b5b1db2
2 changed files with 6 additions and 3 deletions

View File

@ -534,8 +534,9 @@ void Plane::Log_Write_Vehicle_Startup_Messages()
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
#if HAL_QUADPLANE_ENABLED
if (quadplane.initialised) {
logger.Write_MessageF("QuadPlane Frame: %s/%s", quadplane.motors->get_frame_string(),
quadplane.motors->get_type_string());
char frame_and_type_string[30];
quadplane.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
logger.Write_MessageF("QuadPlane %s", frame_and_type_string);
}
#endif
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);

View File

@ -727,7 +727,9 @@ bool QuadPlane::setup(void)
// param count will have changed
AP_Param::invalidate_count();
gcs().send_text(MAV_SEVERITY_INFO, "QuadPlane initialised, class: %s, type: %s", motors->get_frame_string(), motors->get_type_string());
char frame_and_type_string[30];
motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
gcs().send_text(MAV_SEVERITY_INFO, "QuadPlane initialised, %s", frame_and_type_string);
initialised = true;
return true;
}