AP_Motors: allow Copter to fly the tailsitter motors class

This commit is contained in:
Andrew Tridgell 2017-02-11 22:27:50 +11:00
parent c62c64d27b
commit ac2a9c4b4a
1 changed files with 4 additions and 0 deletions

View File

@ -64,6 +64,10 @@ void AP_MotorsTailsitter::output_to_motors()
SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, _elevator*SERVO_OUTPUT_RANGE);
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, _rudder*SERVO_OUTPUT_RANGE);
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, _throttle*THROTTLE_RANGE);
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
SRV_Channels::calc_pwm();
SRV_Channels::output_ch_all();
#endif
}
// calculate outputs to the motors