diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 5a316b6fa6..a6f444075f 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -831,7 +831,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: FRAME_CLASS // @DisplayName: Frame Class // @Description: Controls major frame class for multicopter component - // @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 10:BiCopter, 11:Heli_Dual, 12:DodecaHexa, 13:HeliQuad + // @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 10:BiCopter, 11:Heli_Dual, 12:DodecaHexa, 13:HeliQuad, 14:Deca // @User: Standard // @RebootRequired: True AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, DEFAULT_FRAME_CLASS), diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 230ea2ebab..8c9526dde3 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -466,6 +466,8 @@ MAV_TYPE Copter::get_frame_mav_type() 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; @@ -501,6 +503,8 @@ const char* Copter::get_frame_string() return "TAILSITTER"; case AP_Motors::MOTOR_FRAME_DODECAHEXA: return "DODECA_HEXA"; + case AP_Motors::MOTOR_FRAME_DECA: + return "DECA"; case AP_Motors::MOTOR_FRAME_UNDEFINED: default: return "UNKNOWN"; @@ -520,6 +524,7 @@ void Copter::allocate_motors(void) case AP_Motors::MOTOR_FRAME_OCTA: case AP_Motors::MOTOR_FRAME_OCTAQUAD: case AP_Motors::MOTOR_FRAME_DODECAHEXA: + case AP_Motors::MOTOR_FRAME_DECA: default: motors = new AP_MotorsMatrix(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix::var_info;