mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
ArduCopter: tidy frame description strings
Before: AP: Frame: TRI/ After: AP: Frame: TRI
This commit is contained in:
parent
c28a03728d
commit
c2c013964d
@ -570,8 +570,9 @@ void GCS_MAVLINK_Copter::send_banner()
|
||||
send_text(MAV_SEVERITY_INFO, "motors not allocated");
|
||||
return;
|
||||
}
|
||||
send_text(MAV_SEVERITY_INFO, "Frame: %s/%s", copter.motors->get_frame_string(),
|
||||
copter.motors->get_type_string());
|
||||
char frame_and_type_string[30];
|
||||
copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
|
||||
send_text(MAV_SEVERITY_INFO, "%s", frame_and_type_string);
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Copter::handle_command_ack(const mavlink_message_t &msg)
|
||||
|
@ -547,7 +547,9 @@ const struct LogStructure Copter::log_structure[] = {
|
||||
void Copter::Log_Write_Vehicle_Startup_Messages()
|
||||
{
|
||||
// only 200(?) bytes are guaranteed by AP_Logger
|
||||
logger.Write_MessageF("Frame: %s/%s", motors->get_frame_string(), motors->get_type_string());
|
||||
char frame_and_type_string[30];
|
||||
copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
|
||||
logger.Write_MessageF("%s", frame_and_type_string);
|
||||
logger.Write_Mode((uint8_t)flightmode->mode_number(), control_mode_reason);
|
||||
ahrs.Log_Write_Home_And_Origin();
|
||||
gps.Write_AP_Logger_Log_Startup_messages();
|
||||
|
Loading…
Reference in New Issue
Block a user