diff --git a/libraries/AP_Motors/AP_Motors.h b/libraries/AP_Motors/AP_Motors.h
index 0243666a53..fa93d194a6 100644
--- a/libraries/AP_Motors/AP_Motors.h
+++ b/libraries/AP_Motors/AP_Motors.h
@@ -11,3 +11,4 @@
#include "AP_MotorsCoax.h"
#include "AP_MotorsTailsitter.h"
#include "AP_Motors6DOF.h"
+#include "AP_MotorsMatrixTS.h"
diff --git a/libraries/AP_Motors/AP_MotorsMatrixTS.cpp b/libraries/AP_Motors/AP_MotorsMatrixTS.cpp
new file mode 100644
index 0000000000..32bd0bf0c7
--- /dev/null
+++ b/libraries/AP_Motors/AP_MotorsMatrixTS.cpp
@@ -0,0 +1,125 @@
+/*
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+ */
+
+/*
+ * AP_MotorsMatrixTS.cpp - tailsitters with multicopter motor configuration
+ */
+
+#include
+#include
+#include "AP_MotorsMatrixTS.h"
+
+extern const AP_HAL::HAL& hal;
+
+#define SERVO_OUTPUT_RANGE 4500
+
+// output a thrust to all motors that match a given motor mask. This
+// is used to control motors enabled for forward flight. Thrust is in
+// the range 0 to 1
+void AP_MotorsMatrixTS::output_motor_mask(float thrust, uint8_t mask, float rudder_dt)
+{
+ const int16_t pwm_min = get_pwm_output_min();
+ const int16_t pwm_range = get_pwm_output_max() - pwm_min;
+
+ for (uint8_t i=0; i
+#include
+#include
+#include "AP_MotorsMatrix.h"
+
+/// @class AP_MotorsMatrix
+class AP_MotorsMatrixTS : public AP_MotorsMatrix {
+public:
+
+ AP_MotorsMatrixTS(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
+ AP_MotorsMatrix(loop_rate, speed_hz) {
+ AP_Param::setup_object_defaults(this, var_info);
+ };
+
+ virtual void output_to_motors() override;
+
+ virtual void output_motor_mask(float thrust, uint8_t mask, float rudder_dt) override;
+
+protected:
+ // configures the motors for the defined frame_class and frame_type
+ virtual void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) override;
+
+ // calculate motor outputs
+ void output_armed_stabilizing() override;
+};