mirror of https://github.com/ArduPilot/ardupilot
Copter: return MAV_TYPE as quadcopter by default
This allows the GCSs to know that the firmware is for a multicopter
This commit is contained in:
parent
1432763ca5
commit
b1e494a209
|
@ -497,6 +497,7 @@ uint8_t 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:
|
||||
|
@ -511,9 +512,6 @@ uint8_t Copter::get_frame_mav_type()
|
|||
case AP_Motors::MOTOR_FRAME_SINGLE:
|
||||
case AP_Motors::MOTOR_FRAME_COAX:
|
||||
return MAV_TYPE_COAXIAL;
|
||||
case AP_Motors::MOTOR_FRAME_UNDEFINED:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
// unknown frame so return generic
|
||||
return MAV_TYPE_GENERIC;
|
||||
|
|
Loading…
Reference in New Issue