mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
Plane: Quadplane: use get_frame_and_type_string
This commit is contained in:
parent
7aca392dad
commit
ca1b5b1db2
@ -534,8 +534,9 @@ void Plane::Log_Write_Vehicle_Startup_Messages()
|
|||||||
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
Log_Write_Startup(TYPE_GROUNDSTART_MSG);
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
if (quadplane.initialised) {
|
if (quadplane.initialised) {
|
||||||
logger.Write_MessageF("QuadPlane Frame: %s/%s", quadplane.motors->get_frame_string(),
|
char frame_and_type_string[30];
|
||||||
quadplane.motors->get_type_string());
|
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
|
#endif
|
||||||
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
|
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
|
||||||
|
@ -727,7 +727,9 @@ bool QuadPlane::setup(void)
|
|||||||
// param count will have changed
|
// param count will have changed
|
||||||
AP_Param::invalidate_count();
|
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;
|
initialised = true;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user