From c62ce95768c7f0a63c87d8f6244435b7c8779e47 Mon Sep 17 00:00:00 2001
From: rmackay9 <rmackay9@yahoo.com>
Date: Sat, 21 Apr 2012 23:07:57 +0900
Subject: [PATCH] AP_Motors - allow tail servo to be reversed.  Closes
 ArduCopter issue #228

---
 libraries/AP_Motors/AP_MotorsTri.cpp | 6 +++++-
 1 file changed, 5 insertions(+), 1 deletion(-)

diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp
index 1f973dd80..34bcbc445 100644
--- a/libraries/AP_Motors/AP_MotorsTri.cpp
+++ b/libraries/AP_Motors/AP_MotorsTri.cpp
@@ -128,7 +128,11 @@ void AP_MotorsTri::output_armed()
 
 	// also send out to tail command (we rely on any auto pilot to have updated the rc_yaw->radio_out to the correct value)
 	// note we do not save the radio_out to the motor_out array so it may not appear in the ch7out in the status screen of the mission planner
-	_rc->OutputCh(AP_MOTORS_CH_TRI_YAW, _rc_yaw->radio_out);
+	if( _rc_yaw->get_reverse() == true ) {
+		_rc->OutputCh(AP_MOTORS_CH_TRI_YAW, _rc_yaw->radio_trim - (_rc_yaw->radio_out - _rc_yaw->radio_trim));
+	}else{
+		_rc->OutputCh(AP_MOTORS_CH_TRI_YAW, _rc_yaw->radio_out);
+	}
 		
 	// InstantPWM
 	if( _speed_hz == AP_MOTORS_SPEED_INSTANT_PWM ) {
-- 
GitLab