From 1a76c28655011b2ad618be40bf4c268b76ae698a Mon Sep 17 00:00:00 2001 From: murata Date: Sun, 14 May 2017 10:15:02 +0900 Subject: [PATCH] Copter: add dodeca-hexa --- ArduCopter/Parameters.cpp | 2 +- ArduCopter/system.cpp | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 4f115c0480..1942441555 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -987,7 +987,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 + // @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 6:Heli, 7:Tri, 8:SingleCopter, 9:CoaxCopter, 11:Heli_Dual, 12:DodecaHexa // @User: Standard // @RebootRequired: True AP_GROUPINFO("FRAME_CLASS", 15, ParametersG2, frame_class, 0), diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 118cc2942f..b1cac7d13d 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -536,6 +536,8 @@ uint8_t Copter::get_frame_mav_type() 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_HEXAROTOR; } // unknown frame so return generic return MAV_TYPE_GENERIC; @@ -567,6 +569,8 @@ const char* Copter::get_frame_string() return "COAX"; case AP_Motors::MOTOR_FRAME_TAILSITTER: return "TAILSITTER"; + case AP_Motors::MOTOR_FRAME_DODECAHEXA: + return "DODECA_HEXA"; case AP_Motors::MOTOR_FRAME_UNDEFINED: default: return "UNKNOWN"; @@ -585,6 +589,7 @@ void Copter::allocate_motors(void) case AP_Motors::MOTOR_FRAME_Y6: case AP_Motors::MOTOR_FRAME_OCTA: case AP_Motors::MOTOR_FRAME_OCTAQUAD: + case AP_Motors::MOTOR_FRAME_DODECAHEXA: default: motors = new AP_MotorsMatrix(MAIN_LOOP_RATE); motors_var_info = AP_MotorsMatrix::var_info;