From 015b971ccb42cb9696f337fb7f5e93db1065fbd5 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 19 Jun 2021 19:12:48 +0100 Subject: [PATCH] Plane: add new dynamic mixer frame class --- ArduPlane/quadplane.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 27c9c33255..3f80957ea8 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -149,7 +149,7 @@ const AP_Param::GroupInfo QuadPlane::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, 7:Tri, 10: TailSitter, 12:DodecaHexa, 14:Deca, 15:Scripting Matrix + // @Values: 0:Undefined, 1:Quad, 2:Hexa, 3:Octa, 4:OctaQuad, 5:Y6, 7:Tri, 10: TailSitter, 12:DodecaHexa, 14:Deca, 15:Scripting Matrix, 17:Dynamic Scripting Matrix // @User: Standard AP_GROUPINFO("FRAME_CLASS", 46, QuadPlane, frame_class, 1), @@ -726,6 +726,8 @@ bool QuadPlane::setup(void) AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER); break; case AP_Motors::MOTOR_FRAME_TAILSITTER: + case AP_Motors::MOTOR_FRAME_SCRIPTING_MATRIX: + case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: break; default: AP_BoardConfig::config_error("Unsupported Q_FRAME_CLASS %u", frame_class); @@ -746,6 +748,12 @@ bool QuadPlane::setup(void) rotation = ROTATION_PITCH_90; } break; + case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: +#ifdef ENABLE_SCRIPTING + motors = new AP_MotorsMatrix_Scripting_Dynamic(plane.scheduler.get_loop_rate_hz()); + motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info; +#endif // ENABLE_SCRIPTING + break; default: motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz(), rc_speed); motors_var_info = AP_MotorsMatrix::var_info;