mirror of https://github.com/ArduPilot/ardupilot
Copter: allow for flight mode UI when FRAME_CLASS=0
this makes the user experience of a first time install nicer for copters/helis. At the moment the user finds the GCS is not functional, for example flight mode drop-downs don't display. This can be confusing as the user doesn't know about the link between displaying flight modes and the FRAME_CLASS
This commit is contained in:
parent
d91cbf08c8
commit
8cabcfc750
|
@ -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();
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue