fixed throttle range for motor arming, removed negative sign for roll in acro mode now that APM orientation is decided

git-svn-id: https://arducopter.googlecode.com/svn/trunk@43 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
CaranchoEngineering 2010-07-14 08:22:46 +00:00
parent 8a82413080
commit c0edb56fef
1 changed files with 6 additions and 13 deletions

View File

@ -323,14 +323,7 @@ void Rate_control()
float currentRollRate, currentPitchRate, currentYawRate; float currentRollRate, currentPitchRate, currentYawRate;
// ROLL CONTROL // ROLL CONTROL
currentRollRate = read_adc(0); // I need a positive sign here
// NOTE: We need to test THIS !! Plaese CHECK
#ifdef FLIGHT_MODE_+
currentRollRate = read_adc(0); // I need a positive sign here
#endif
#ifdef FLIGHT_MODE_X
currentRollRate = -read_adc(0); // Original from Ted
#endif
err_roll = ((ch_roll-1500) * xmitFactor) - currentRollRate; err_roll = ((ch_roll-1500) * xmitFactor) - currentRollRate;
@ -699,7 +692,7 @@ void loop(){
command_rx_yaw_diff = 0; command_rx_yaw_diff = 0;
} }
// Arm motor output // Arm motor output
if (ch_throttle < 1100) { if (ch_throttle < 1200) {
control_yaw = 0; control_yaw = 0;
if (ch_yaw > 1800) if (ch_yaw > 1800)
motorArmed = 1; motorArmed = 1;
@ -719,10 +712,10 @@ void loop(){
backMotor = ch_throttle - control_pitch + control_yaw; backMotor = ch_throttle - control_pitch + control_yaw;
#endif #endif
#ifdef FLIGHT_MODE_X #ifdef FLIGHT_MODE_X
frontMotor = ch_throttle + control_roll - control_pitch - control_yaw; // front left motor frontMotor = ch_throttle + control_roll + control_pitch - control_yaw; // front left motor
rightMotor = ch_throttle - control_roll - control_pitch + control_yaw; // front right motor rightMotor = ch_throttle - control_roll + control_pitch + control_yaw; // front right motor
leftMotor = ch_throttle + control_roll + control_pitch + control_yaw; // rear left motor leftMotor = ch_throttle + control_roll - control_pitch + control_yaw; // rear left motor
backMotor = ch_throttle - control_roll + control_pitch - control_yaw; // rear right motor backMotor = ch_throttle - control_roll - control_pitch - control_yaw; // rear right motor
#endif #endif
} }
if (motorArmed == 0) { if (motorArmed == 0) {