From af08379d1ba7734c116e64b3f8a247842d5c2f6d Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Fri, 3 Jan 2020 11:54:40 +0000 Subject: [PATCH] AP_Motors: MatrixTS remove output_to_motors --- libraries/AP_Motors/AP_MotorsMatrixTS.cpp | 11 ----------- libraries/AP_Motors/AP_MotorsMatrixTS.h | 2 -- 2 files changed, 13 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMatrixTS.cpp b/libraries/AP_Motors/AP_MotorsMatrixTS.cpp index 7fe7a30e84..d8511d2ae6 100644 --- a/libraries/AP_Motors/AP_MotorsMatrixTS.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrixTS.cpp @@ -25,17 +25,6 @@ extern const AP_HAL::HAL& hal; #define SERVO_OUTPUT_RANGE 4500 -void AP_MotorsMatrixTS::output_to_motors() -{ - // calls calc_thrust_to_pwm(_thrust_rpyt_out[i]) for each enabled motor - AP_MotorsMatrix::output_to_motors(); - - // also actuate control surfaces - SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, -_yaw_in * SERVO_OUTPUT_RANGE); - SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, _pitch_in * SERVO_OUTPUT_RANGE); - SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, _roll_in * SERVO_OUTPUT_RANGE); -} - // output_armed - sends commands to the motors // includes new scaling stability patch void AP_MotorsMatrixTS::output_armed_stabilizing() diff --git a/libraries/AP_Motors/AP_MotorsMatrixTS.h b/libraries/AP_Motors/AP_MotorsMatrixTS.h index f3da313d81..edae3f6a7a 100644 --- a/libraries/AP_Motors/AP_MotorsMatrixTS.h +++ b/libraries/AP_Motors/AP_MotorsMatrixTS.h @@ -17,8 +17,6 @@ public: AP_Param::setup_object_defaults(this, var_info); }; - virtual void output_to_motors() override; - protected: bool use_standard_matrix; // True to use normal matrix mixers with yaw torque