AP_Motors: MatrixTS remove output_to_motors

This commit is contained in:
Peter Hall 2020-01-03 11:54:40 +00:00 committed by Andrew Tridgell
parent 615695c1bc
commit af08379d1b
2 changed files with 0 additions and 13 deletions

View File

@ -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()

View File

@ -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