diff --git a/ArduCopter/GCS_Copter.cpp b/ArduCopter/GCS_Copter.cpp index 166f6b8f6c..7721e5e746 100644 --- a/ArduCopter/GCS_Copter.cpp +++ b/ArduCopter/GCS_Copter.cpp @@ -10,7 +10,7 @@ uint8_t GCS_Copter::sysid_this_mav() const const char* GCS_Copter::frame_string() const { if (copter.motors == nullptr) { - return "motors not allocated"; + return "MultiCopter"; } return copter.motors->get_frame_string(); } diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index c88d528986..a1e8b5d0b8 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -6,10 +6,24 @@ MAV_TYPE GCS_Copter::frame_type() const { + /* + for GCS don't give MAV_TYPE_GENERIC as the GCS would have no + information and won't display UIs such as flight mode + selection + */ +#if FRAME_CONFIG == HELI_FRAME + const MAV_TYPE mav_type_default = MAV_TYPE_HELICOPTER; +#else + const MAV_TYPE mav_type_default = MAV_TYPE_QUADROTOR; +#endif if (copter.motors == nullptr) { - return MAV_TYPE_GENERIC; + return mav_type_default; } - return copter.motors->get_frame_mav_type(); + MAV_TYPE mav_type = copter.motors->get_frame_mav_type(); + if (mav_type == MAV_TYPE_GENERIC) { + mav_type = mav_type_default; + } + return mav_type; } MAV_MODE GCS_MAVLINK_Copter::base_mode() const