From 0d1f184076417d3102c90761967e2a52886ff133 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Fri, 27 May 2011 17:58:39 +0000 Subject: [PATCH] minor changes git-svn-id: https://arducopter.googlecode.com/svn/trunk@2420 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/defines.h | 1 + ArduCopterMega/motors_hexa.pde | 8 ++++++++ 2 files changed, 9 insertions(+) diff --git a/ArduCopterMega/defines.h b/ArduCopterMega/defines.h index 91ff2c8d47..a85710fb67 100644 --- a/ArduCopterMega/defines.h +++ b/ArduCopterMega/defines.h @@ -39,6 +39,7 @@ #define GPS_PROTOCOL_MTK 4 #define GPS_PROTOCOL_HIL 5 #define GPS_PROTOCOL_MTK16 6 +#define GPS_PROTOCOL_AUTO 7 // Radio channels // Note channels are from 0! diff --git a/ArduCopterMega/motors_hexa.pde b/ArduCopterMega/motors_hexa.pde index df29ffb692..32c7a1942b 100644 --- a/ArduCopterMega/motors_hexa.pde +++ b/ArduCopterMega/motors_hexa.pde @@ -56,6 +56,14 @@ void output_motors_armed() motor_out[CH_1] -= g.rc_4.pwm_out; // CW motor_out[CH_8] -= g.rc_4.pwm_out; // CW + // limit output so motors don't stop + motor_out[CH_1] = max(motor_out[CH_1], out_min); + motor_out[CH_2] = max(motor_out[CH_2], out_min); + motor_out[CH_3] = max(motor_out[CH_3], out_min); + motor_out[CH_4] = max(motor_out[CH_4], out_min); + motor_out[CH_7] = max(motor_out[CH_7], out_min); + motor_out[CH_8] = max(motor_out[CH_8], out_min); + // Send commands to motors if(g.rc_3.servo_out > 0){ APM_RC.OutputCh(CH_1, motor_out[CH_1]);