diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 0a2c539cae..276752a67b 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -42,6 +42,7 @@ #include #include // Mission command library #include // Attitude control library +#include // 6DoF Attitude control library #include // Attitude control library for traditional helicopter #include // Position control library #include // AP Motors library diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index c8f1dfc6bc..712ceae844 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -864,7 +864,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, 14:Deca, 15:Scripting Matrix + // @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, 15:Scripting Matrix, 16:6DoF Scripting // @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 5f33d57db2..279b10bbb9 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -484,6 +484,12 @@ void Copter::allocate_motors(void) motors = new AP_MotorsTailsitter(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsTailsitter::var_info; break; + case AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING: +#ifdef ENABLE_SCRIPTING + motors = new AP_MotorsMatrix_6DoF_Scripting(copter.scheduler.get_loop_rate_hz()); + motors_var_info = AP_MotorsMatrix_6DoF_Scripting::var_info; +#endif // ENABLE_SCRIPTING + break; #else // FRAME_CONFIG == HELI_FRAME case AP_Motors::MOTOR_FRAME_HELI_DUAL: motors = new AP_MotorsHeli_Dual(copter.scheduler.get_loop_rate_hz()); @@ -518,8 +524,15 @@ void Copter::allocate_motors(void) const struct AP_Param::GroupInfo *ac_var_info; #if FRAME_CONFIG != HELI_FRAME - attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s()); - ac_var_info = AC_AttitudeControl_Multi::var_info; + if ((AP_Motors::motor_frame_class)g2.frame_class.get() == AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING) { +#ifdef ENABLE_SCRIPTING + attitude_control = new AC_AttitudeControl_Multi_6DoF(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s()); + ac_var_info = AC_AttitudeControl_Multi_6DoF::var_info; +#endif // ENABLE_SCRIPTING + } else { + attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s()); + ac_var_info = AC_AttitudeControl_Multi::var_info; + } #else attitude_control = new AC_AttitudeControl_Heli(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s()); ac_var_info = AC_AttitudeControl_Heli::var_info;