From cb687a6fffccbd986facaf3d856978a96b1f1215 Mon Sep 17 00:00:00 2001 From: Mark Whitehorn Date: Thu, 5 Nov 2020 13:00:12 -0700 Subject: [PATCH] Copter: move get_frame_string to Motors class --- ArduCopter/Copter.h | 1 + ArduCopter/GCS_Copter.cpp | 2 +- ArduCopter/GCS_Mavlink.cpp | 2 +- ArduCopter/Log.cpp | 2 +- ArduCopter/system.cpp | 30 ++++++++++++++++++++++++++++++ 5 files changed, 34 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 0a2c539cae..976c0664b7 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -863,6 +863,7 @@ private: bool ekf_alt_ok() const; void update_auto_armed(); bool should_log(uint32_t mask); + MAV_TYPE get_frame_mav_type(); const char* get_frame_string() const; void allocate_motors(void); bool is_tradheli() const; diff --git a/ArduCopter/GCS_Copter.cpp b/ArduCopter/GCS_Copter.cpp index 8fb9bfcb18..9657a94961 100644 --- a/ArduCopter/GCS_Copter.cpp +++ b/ArduCopter/GCS_Copter.cpp @@ -9,7 +9,7 @@ uint8_t GCS_Copter::sysid_this_mav() const const char* GCS_Copter::frame_string() const { - return copter.get_frame_string(); + return copter.motors->get_frame_string(); } bool GCS_Copter::simple_input_active() const diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index b26533aef0..faf22e0d5e 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -548,7 +548,7 @@ bool GCS_MAVLINK_Copter::params_ready() const void GCS_MAVLINK_Copter::send_banner() { GCS_MAVLINK::send_banner(); - send_text(MAV_SEVERITY_INFO, "Frame: %s", copter.get_frame_string()); + send_text(MAV_SEVERITY_INFO, "Frame: %s", copter.motors->get_frame_string()); } // a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 980e85ab5d..3eb4c7227c 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -617,7 +617,7 @@ 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", get_frame_string()); + logger.Write_MessageF("Frame: %s, Type: %s", motors->get_frame_string(), motors->get_type_string()); logger.Write_Mode((uint8_t)control_mode, control_mode_reason); ahrs.Log_Write_Home_And_Origin(); gps.Write_AP_Logger_Log_Startup_messages(); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 7023c62c72..c54887c411 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -484,6 +484,36 @@ const char* Copter::get_frame_string() const default: return "UNKNOWN"; } +// return MAV_TYPE corresponding to frame class +MAV_TYPE Copter::get_frame_mav_type() +{ + switch ((AP_Motors::motor_frame_class)g2.frame_class.get()) { + case AP_Motors::MOTOR_FRAME_QUAD: + case AP_Motors::MOTOR_FRAME_UNDEFINED: + return MAV_TYPE_QUADROTOR; + case AP_Motors::MOTOR_FRAME_HEXA: + case AP_Motors::MOTOR_FRAME_Y6: + return MAV_TYPE_HEXAROTOR; + case AP_Motors::MOTOR_FRAME_OCTA: + case AP_Motors::MOTOR_FRAME_OCTAQUAD: + return MAV_TYPE_OCTOROTOR; + case AP_Motors::MOTOR_FRAME_HELI: + case AP_Motors::MOTOR_FRAME_HELI_DUAL: + case AP_Motors::MOTOR_FRAME_HELI_QUAD: + return MAV_TYPE_HELICOPTER; + case AP_Motors::MOTOR_FRAME_TRI: + return MAV_TYPE_TRICOPTER; + case AP_Motors::MOTOR_FRAME_SINGLE: + case AP_Motors::MOTOR_FRAME_COAX: + case AP_Motors::MOTOR_FRAME_TAILSITTER: + return MAV_TYPE_COAXIAL; + case AP_Motors::MOTOR_FRAME_DODECAHEXA: + return MAV_TYPE_DODECAROTOR; + case AP_Motors::MOTOR_FRAME_DECA: + return MAV_TYPE_DECAROTOR; + } + // unknown frame so return generic + return MAV_TYPE_GENERIC; } /*