diff --git a/ArduCopter/heli.pde b/ArduCopter/heli.pde deleted file mode 100644 index 7940adee98..0000000000 --- a/ArduCopter/heli.pde +++ /dev/null @@ -1,334 +0,0 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -#if FRAME_CONFIG == HELI_FRAME - -#define HELI_SERVO_AVERAGING_DIGITAL 0 // 250Hz -#define HELI_SERVO_AVERAGING_ANALOG 2 // 125Hz - -static bool heli_swash_initialised = false; -static int heli_throttle_mid = 0; // throttle mid point in pwm form (i.e. 0 ~ 1000) -static float heli_collective_scalar = 1; // throttle scalar to convert pwm form (i.e. 0 ~ 1000) passed in to actual servo range (i.e 1250~1750 would be 500) - -// heli_servo_averaging: -// 0 or 1 = no averaging, 250hz -// 2 = average two samples, 125hz -// 3 = averaging three samples = 83.3 hz -// 4 = averaging four samples = 62.5 hz -// 5 = averaging 5 samples = 50hz -// digital = 0 / 250hz, analog = 2 / 83.3 - -// reset swash for maximum movements - used for set-up -static void heli_reset_swash() -{ - // free up servo ranges - g.heli_servo_1.radio_min = 1000; - g.heli_servo_1.radio_max = 2000; - g.heli_servo_2.radio_min = 1000; - g.heli_servo_2.radio_max = 2000; - g.heli_servo_3.radio_min = 1000; - g.heli_servo_3.radio_max = 2000; - - if (!g.heli_h1_swash_enabled){ //CCPM Swashplate, perform servo control mixing - - // roll factors - heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle)); - heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle)); - heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle)); - - // pitch factors - heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle)); - heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle)); - heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle)); - - // collective factors - heli_collectiveFactor[CH_1] = 1; - heli_collectiveFactor[CH_2] = 1; - heli_collectiveFactor[CH_3] = 1; - - }else{ //H1 Swashplate, keep servo outputs seperated - - // roll factors - heli_rollFactor[CH_1] = 1; - heli_rollFactor[CH_2] = 0; - heli_rollFactor[CH_3] = 0; - - // pitch factors - heli_pitchFactor[CH_1] = 0; - heli_pitchFactor[CH_2] = 1; - heli_pitchFactor[CH_3] = 0; - - // collective factors - heli_collectiveFactor[CH_1] = 0; - heli_collectiveFactor[CH_2] = 0; - heli_collectiveFactor[CH_3] = 1; - } - - // set throttle scaling - heli_collective_scalar = ((float)(g.rc_3.radio_max - g.rc_3.radio_min))/1000.0; - - // we must be in set-up mode so mark swash as uninitialised - heli_swash_initialised = false; -} - -// initialise the swash -static void heli_init_swash() -{ - int i; - - // swash servo initialisation - g.heli_servo_1.set_range(0,1000); - g.heli_servo_2.set_range(0,1000); - g.heli_servo_3.set_range(0,1000); - g.heli_servo_4.set_angle(4500); - - // ensure g.heli_coll values are reasonable - if( g.heli_collective_min >= g.heli_collective_max ) { - g.heli_collective_min = 1000; - g.heli_collective_max = 2000; - } - g.heli_collective_mid = constrain(g.heli_collective_mid, g.heli_collective_min, g.heli_collective_max); - - // calculate throttle mid point - heli_throttle_mid = ((float)(g.heli_collective_mid-g.heli_collective_min))/((float)(g.heli_collective_max-g.heli_collective_min))*1000.0; - - // determine scalar throttle input - heli_collective_scalar = ((float)(g.heli_collective_max-g.heli_collective_min))/1000.0; - - if (!g.heli_h1_swash_enabled){ //CCPM Swashplate, perform control mixing - - // roll factors - heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle)); - heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle)); - heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle)); - - // pitch factors - heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle)); - heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle)); - heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle)); - - // collective factors - heli_collectiveFactor[CH_1] = 1; - heli_collectiveFactor[CH_2] = 1; - heli_collectiveFactor[CH_3] = 1; - - }else{ //H1 Swashplate, keep servo outputs seperated - - // roll factors - heli_rollFactor[CH_1] = 1; - heli_rollFactor[CH_2] = 0; - heli_rollFactor[CH_3] = 0; - - // pitch factors - heli_pitchFactor[CH_1] = 0; - heli_pitchFactor[CH_2] = 1; - heli_pitchFactor[CH_3] = 0; - - // collective factors - heli_collectiveFactor[CH_1] = 0; - heli_collectiveFactor[CH_2] = 0; - heli_collectiveFactor[CH_3] = 1; - } - - // servo min/max values - g.heli_servo_1.radio_min = 1000; - g.heli_servo_1.radio_max = 2000; - g.heli_servo_2.radio_min = 1000; - g.heli_servo_2.radio_max = 2000; - g.heli_servo_3.radio_min = 1000; - g.heli_servo_3.radio_max = 2000; - - // reset the servo averaging - for( i=0; i<=3; i++ ) - heli_servo_out[i] = 0; - - // double check heli_servo_averaging is reasonable - if( g.heli_servo_averaging < 0 || g.heli_servo_averaging > 5 ) { - g.heli_servo_averaging = 0; - g.heli_servo_averaging.save(); - } - - // mark swash as initialised - heli_swash_initialised = true; -} - -static void heli_move_servos_to_mid() -{ - // call multiple times to force through the servo averaging - for( int i=0; i<5; i++ ) { - heli_move_swash(0,0,500,0); - delay(20); - } -} - -// -// heli_move_swash - moves swash plate to attitude of parameters passed in -// - expected ranges: -// roll : -4500 ~ 4500 -// pitch: -4500 ~ 4500 -// collective: 0 ~ 1000 -// yaw: -4500 ~ 4500 -// -static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out) -{ - int yaw_offset = 0; - int coll_out_scaled; - - if( g.heli_servo_manual == 1 ) { // are we in manual servo mode? (i.e. swash set-up mode)? - // check if we need to freeup the swash - if( heli_swash_initialised ) { - heli_reset_swash(); - } - coll_out_scaled = coll_out * heli_collective_scalar + g.rc_3.radio_min - 1000; - }else{ // regular flight mode - - // check if we need to reinitialise the swash - if( !heli_swash_initialised ) { - heli_init_swash(); - } - - // ensure values are acceptable: - roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max); - pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max); - coll_out = constrain(coll_out, 0, 1000); - coll_out_scaled = coll_out * heli_collective_scalar + g.heli_collective_min - 1000; - - // rescale roll_out and pitch-out into the min and max ranges to provide linear motion - // across the input range instead of stopping when the input hits the constrain value - // these calculations are based on an assumption of the user specified roll_max and pitch_max - // coming into this equation at 4500 or less, and based on the original assumption of the - // total g.heli_servo_x.servo_out range being -4500 to 4500. - roll_out = (-g.heli_roll_max + (float)( 2 * g.heli_roll_max * (roll_out + 4500.0)/9000.0)); - pitch_out = (-g.heli_pitch_max + (float)(2 * g.heli_pitch_max * (pitch_out + 4500.0)/9000.0)); - - - // rudder feed forward based on collective - #if HIL_MODE == HIL_MODE_DISABLED // don't do rudder feed forward in simulator - if( !g.heli_ext_gyro_enabled ) { - yaw_offset = g.heli_collective_yaw_effect * abs(coll_out_scaled - heli_throttle_mid); - } - #endif - } - - // swashplate servos - g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + heli_collectiveFactor[CH_1] * coll_out_scaled + (g.heli_servo_1.radio_trim-1500) + g.heli_h1_swash_enabled * 500; - g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + heli_collectiveFactor[CH_2] * coll_out_scaled + (g.heli_servo_2.radio_trim-1500) + g.heli_h1_swash_enabled * 500; - g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + heli_collectiveFactor[CH_3] * coll_out_scaled + (g.heli_servo_3.radio_trim-1500); - g.heli_servo_4.servo_out = yaw_out + yaw_offset; - - // use servo_out to calculate pwm_out and radio_out - g.heli_servo_1.calc_pwm(); - g.heli_servo_2.calc_pwm(); - g.heli_servo_3.calc_pwm(); - g.heli_servo_4.calc_pwm(); - - // add the servo values to the averaging - heli_servo_out[0] += g.heli_servo_1.radio_out; - heli_servo_out[1] += g.heli_servo_2.radio_out; - heli_servo_out[2] += g.heli_servo_3.radio_out; - heli_servo_out[3] += g.heli_servo_4.radio_out; - heli_servo_out_count++; - - // is it time to move the servos? - if( heli_servo_out_count >= g.heli_servo_averaging ) { - - // average the values if necessary - if( g.heli_servo_averaging >= 2 ) { - heli_servo_out[0] /= g.heli_servo_averaging; - heli_servo_out[1] /= g.heli_servo_averaging; - heli_servo_out[2] /= g.heli_servo_averaging; - heli_servo_out[3] /= g.heli_servo_averaging; - } - - // actually move the servos - APM_RC.OutputCh(CH_1, heli_servo_out[0]); - APM_RC.OutputCh(CH_2, heli_servo_out[1]); - APM_RC.OutputCh(CH_3, heli_servo_out[2]); - APM_RC.OutputCh(CH_4, heli_servo_out[3]); - - // output gyro value - if( g.heli_ext_gyro_enabled ) { - APM_RC.OutputCh(CH_7, g.heli_ext_gyro_gain); - } - - #if INSTANT_PWM == 1 - // InstantPWM - APM_RC.Force_Out0_Out1(); - APM_RC.Force_Out2_Out3(); - #endif - - // reset the averaging - heli_servo_out_count = 0; - heli_servo_out[0] = 0; - heli_servo_out[1] = 0; - heli_servo_out[2] = 0; - heli_servo_out[3] = 0; - } -} - -static void init_motors_out() -{ - #if INSTANT_PWM == 0 - APM_RC.SetFastOutputChannels( _BV(CH_1) | _BV(CH_2) | _BV(CH_3) | _BV(CH_4), g.rc_speed ); - #endif -} - -static void motors_output_enable() -{ - APM_RC.enable_out(CH_1); - APM_RC.enable_out(CH_2); - APM_RC.enable_out(CH_3); - APM_RC.enable_out(CH_4); - APM_RC.enable_out(CH_5); - APM_RC.enable_out(CH_6); - APM_RC.enable_out(CH_7); - APM_RC.enable_out(CH_8); -} - -// these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better -static void output_motors_armed() -{ - // if manual override (i.e. when setting up swash), pass pilot commands straight through to swash - if( g.heli_servo_manual == 1 ) { - g.rc_1.servo_out = g.rc_1.control_in; - g.rc_2.servo_out = g.rc_2.control_in; - g.rc_3.servo_out = g.rc_3.control_in; - g.rc_4.servo_out = g.rc_4.control_in; - } - - //static int counter = 0; - g.rc_1.calc_pwm(); - g.rc_2.calc_pwm(); - g.rc_3.calc_pwm(); - g.rc_4.calc_pwm(); - - heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.servo_out, g.rc_4.servo_out ); -} - -// for helis - armed or disarmed we allow servos to move -static void output_motors_disarmed() -{ - if(g.rc_3.control_in > 0){ - // we have pushed up the throttle, remove safety - motor_auto_armed = true; - } - - output_motors_armed(); -} - -static void output_motor_test() -{ -} - -// heli_angle_boost - adds a boost depending on roll/pitch values -// equivalent of quad's angle_boost function -// throttle value should be 0 ~ 1000 -static int16_t heli_get_angle_boost(int throttle) -{ - float angle_boost_factor = cos_pitch_x * cos_roll_x; - angle_boost_factor = 1.0 - constrain(angle_boost_factor, .5, 1.0); - int throttle_above_mid = max(throttle - heli_throttle_mid,0); - return throttle + throttle_above_mid*angle_boost_factor; - -} - -#endif // HELI_FRAME diff --git a/ArduCopter/motors_hexa.pde b/ArduCopter/motors_hexa.pde deleted file mode 100644 index 10eae0b73b..0000000000 --- a/ArduCopter/motors_hexa.pde +++ /dev/null @@ -1,241 +0,0 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -#if FRAME_CONFIG == HEXA_FRAME - -static void init_motors_out() -{ - #if INSTANT_PWM == 0 - APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4) - | _BV(MOT_5) | _BV(MOT_6), g.rc_speed); - #endif -} - -static void motors_output_enable() -{ - APM_RC.enable_out(MOT_1); - APM_RC.enable_out(MOT_2); - APM_RC.enable_out(MOT_3); - APM_RC.enable_out(MOT_4); - APM_RC.enable_out(MOT_5); - APM_RC.enable_out(MOT_6); -} - -static void output_motors_armed() -{ - int roll_out, pitch_out; - int out_min = g.rc_3.radio_min; - int out_max = g.rc_3.radio_max; - - // Throttle is 0 to 1000 only - g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE); - - if(g.rc_3.servo_out > 0) - out_min = g.rc_3.radio_min + MINIMUM_THROTTLE; - - g.rc_1.calc_pwm(); - g.rc_2.calc_pwm(); - g.rc_3.calc_pwm(); - g.rc_4.calc_pwm(); - - if(g.frame_orientation == X_FRAME){ - roll_out = g.rc_1.pwm_out / 2; - pitch_out = (float)g.rc_2.pwm_out * .866; - - //left side - motor_out[MOT_2] = g.rc_3.radio_out + g.rc_1.pwm_out; // CCW Middle - motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // CW Front - motor_out[MOT_6] = g.rc_3.radio_out + roll_out - pitch_out; // CW Back - - //right side - motor_out[MOT_1] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW Middle - motor_out[MOT_5] = g.rc_3.radio_out - roll_out + pitch_out; // CCW Front - motor_out[MOT_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW Back - - }else{ - roll_out = (float)g.rc_1.pwm_out * .866; - pitch_out = g.rc_2.pwm_out / 2; - - //Front side - motor_out[MOT_1] = g.rc_3.radio_out + g.rc_2.pwm_out; // CW FRONT - motor_out[MOT_5] = g.rc_3.radio_out + roll_out + pitch_out; // CCW FRONT LEFT - motor_out[MOT_4] = g.rc_3.radio_out - roll_out + pitch_out; // CCW FRONT RIGHT - - //Back side - motor_out[MOT_2] = g.rc_3.radio_out - g.rc_2.pwm_out; // CCW BACK - motor_out[MOT_3] = g.rc_3.radio_out + roll_out - pitch_out; // CW, BACK LEFT - motor_out[MOT_6] = g.rc_3.radio_out - roll_out - pitch_out; // CW BACK RIGHT - } - - // Yaw - motor_out[MOT_2] += g.rc_4.pwm_out; // CCW - motor_out[MOT_5] += g.rc_4.pwm_out; // CCW - motor_out[MOT_4] += g.rc_4.pwm_out; // CCW - - motor_out[MOT_3] -= g.rc_4.pwm_out; // CW - motor_out[MOT_1] -= g.rc_4.pwm_out; // CW - motor_out[MOT_6] -= g.rc_4.pwm_out; // CW - - - // Tridge's stability patch - for (int m = 1; m <= 6; m++){ - int c = ch_of_mot(m); - int c_opp = ch_of_mot(((m-1)^1)+1); // ((m-1)^1)+1 is the opposite motor. c_opp is channel of opposite motor. - if(motor_out[c] > out_max){ - motor_out[c_opp] -= motor_out[c] - out_max; - motor_out[c] = out_max; - } - } - - // limit output so motors don't stop - motor_out[MOT_1] = max(motor_out[MOT_1], out_min); - motor_out[MOT_2] = max(motor_out[MOT_2], out_min); - motor_out[MOT_3] = max(motor_out[MOT_3], out_min); - motor_out[MOT_4] = max(motor_out[MOT_4], out_min); - motor_out[MOT_5] = max(motor_out[MOT_5], out_min); - motor_out[MOT_6] = max(motor_out[MOT_6], out_min); - - #if CUT_MOTORS == ENABLED - // if we are not sending a throttle output, we cut the motors - if(g.rc_3.servo_out == 0){ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - motor_out[MOT_5] = g.rc_3.radio_min; - motor_out[MOT_6] = g.rc_3.radio_min; - } - #endif - - // this filter slows the acceleration of motors vs the deceleration - // Idea by Denny Rowland to help with his Yaw issue - for(int8_t m = 1; m <= 6; m++){ - int c = ch_of_mot(m); - if(motor_filtered[c] < motor_out[c]){ - motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2; - }else{ - // don't filter - motor_filtered[c] = motor_out[c]; - } - } - - APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]); - APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]); - APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]); - - #if INSTANT_PWM == 1 - // InstantPWM - APM_RC.Force_Out0_Out1(); - APM_RC.Force_Out2_Out3(); - APM_RC.Force_Out6_Out7(); - #endif - -} - -static void output_motors_disarmed() -{ - if(g.rc_3.control_in > 0){ - // we have pushed up the throttle - // remove safety - motor_auto_armed = true; - } - - // fill the motor_out[] array for HIL use - for (unsigned char i = 0; i < 8; i++){ - motor_out[i] = g.rc_3.radio_min; - } - - // Send commands to motors - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); -} - -static void output_motor_test() -{ - motors_output_enable(); - - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - motor_out[MOT_5] = g.rc_3.radio_min; - motor_out[MOT_6] = g.rc_3.radio_min; - - if(g.frame_orientation == X_FRAME){ - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - delay(4000); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100); - delay(300); - - } else { /* PLUS_FRAME */ - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - delay(4000); - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100); - delay(300); - } - - APM_RC.OutputCh(MOT_1, motor_out[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_out[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_out[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_out[MOT_4]); - APM_RC.OutputCh(MOT_5, motor_out[MOT_5]); - APM_RC.OutputCh(MOT_6, motor_out[MOT_6]); -} - -#endif diff --git a/ArduCopter/motors_octa.pde b/ArduCopter/motors_octa.pde deleted file mode 100644 index 8f552333d2..0000000000 --- a/ArduCopter/motors_octa.pde +++ /dev/null @@ -1,327 +0,0 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -#if FRAME_CONFIG == OCTA_FRAME - -static void init_motors_out() -{ - #if INSTANT_PWM == 0 - APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4) - | _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8), - g.rc_speed); - #endif -} - -static void motors_output_enable() -{ - APM_RC.enable_out(MOT_1); - APM_RC.enable_out(MOT_2); - APM_RC.enable_out(MOT_3); - APM_RC.enable_out(MOT_4); - APM_RC.enable_out(MOT_5); - APM_RC.enable_out(MOT_6); - APM_RC.enable_out(MOT_7); - APM_RC.enable_out(MOT_8); -} - -static void output_motors_armed() -{ - int roll_out, pitch_out; - int out_min = g.rc_3.radio_min; - int out_max = g.rc_3.radio_max; - - // Throttle is 0 to 1000 only - g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE); - - if(g.rc_3.servo_out > 0) - out_min = g.rc_3.radio_min + MINIMUM_THROTTLE; - - g.rc_1.calc_pwm(); - g.rc_2.calc_pwm(); - g.rc_3.calc_pwm(); - g.rc_4.calc_pwm(); - - if(g.frame_orientation == X_FRAME){ - roll_out = (float)g.rc_1.pwm_out * 0.4; - pitch_out = (float)g.rc_2.pwm_out * 0.4; - - //Front side - motor_out[MOT_1] = g.rc_3.radio_out + g.rc_2.pwm_out - roll_out; // CW FRONT RIGHT - motor_out[MOT_5] = g.rc_3.radio_out + g.rc_2.pwm_out + roll_out; // CCW FRONT LEFT - - //Back side - motor_out[MOT_2] = g.rc_3.radio_out - g.rc_2.pwm_out + roll_out; // CW BACK LEFT - motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out - roll_out; // CCW BACK RIGHT - - //Left side - motor_out[MOT_7] = g.rc_3.radio_out + g.rc_1.pwm_out + pitch_out; // CW LEFT FRONT - motor_out[MOT_6] = g.rc_3.radio_out + g.rc_1.pwm_out - pitch_out; // CCW LEFT BACK - - //Right side - motor_out[MOT_8] = g.rc_3.radio_out - g.rc_1.pwm_out - pitch_out; // CW RIGHT BACK - motor_out[MOT_3] = g.rc_3.radio_out - g.rc_1.pwm_out + pitch_out; // CCW RIGHT FRONT - - }else if(g.frame_orientation == PLUS_FRAME){ - roll_out = (float)g.rc_1.pwm_out * 0.71; - pitch_out = (float)g.rc_2.pwm_out * 0.71; - - //Front side - motor_out[MOT_1] = g.rc_3.radio_out + g.rc_2.pwm_out; // CW FRONT - motor_out[MOT_3] = g.rc_3.radio_out - roll_out + pitch_out; // CCW FRONT RIGHT - motor_out[MOT_5] = g.rc_3.radio_out + roll_out + pitch_out; // CCW FRONT LEFT - - //Left side - motor_out[MOT_7] = g.rc_3.radio_out + g.rc_1.pwm_out; // CW LEFT - - //Right side - motor_out[MOT_8] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW RIGHT - - //Back side - motor_out[MOT_2] = g.rc_3.radio_out - g.rc_2.pwm_out; // CW BACK - motor_out[MOT_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW BACK RIGHT - motor_out[MOT_6] = g.rc_3.radio_out + roll_out - pitch_out; // CCW BACK LEFT - - }else if(g.frame_orientation == V_FRAME){ - - int roll_out2, pitch_out2; - int roll_out3, pitch_out3; - int roll_out4, pitch_out4; - - roll_out = g.rc_1.pwm_out; - pitch_out = g.rc_2.pwm_out; - roll_out2 = (float)g.rc_1.pwm_out * 0.833; - pitch_out2 = (float)g.rc_2.pwm_out * 0.34; - roll_out3 = (float)g.rc_1.pwm_out * 0.666; - pitch_out3 = (float)g.rc_2.pwm_out * 0.32; - roll_out4 = g.rc_1.pwm_out / 2; - pitch_out4 = (float)g.rc_2.pwm_out * 0.98; - - //Front side - motor_out[MOT_7] = g.rc_3.radio_out + g.rc_2.pwm_out - roll_out; // CW FRONT RIGHT - motor_out[MOT_5] = g.rc_3.radio_out + g.rc_2.pwm_out + roll_out; // CCW FRONT LEFT - - //Left side - motor_out[MOT_1] = g.rc_3.radio_out + g.rc_1.pwm_out + pitch_out2; // CW LEFT FRONT - motor_out[MOT_3] = g.rc_3.radio_out + g.rc_1.pwm_out - pitch_out3; // CCW LEFT BACK - - //Right side - motor_out[MOT_2] = g.rc_3.radio_out - g.rc_1.pwm_out - pitch_out3; // CW RIGHT BACK - motor_out[MOT_6] = g.rc_3.radio_out - g.rc_1.pwm_out + pitch_out2; // CCW RIGHT FRONT - - //Back side - motor_out[MOT_8] = g.rc_3.radio_out - g.rc_2.pwm_out + roll_out4; // CW BACK LEFT - motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out - roll_out4; // CCW BACK RIGHT - - } - - // Yaw - motor_out[MOT_3] += g.rc_4.pwm_out; // CCW - motor_out[MOT_4] += g.rc_4.pwm_out; // CCW - motor_out[MOT_5] += g.rc_4.pwm_out; // CCW - motor_out[MOT_6] += g.rc_4.pwm_out; // CCW - - motor_out[MOT_1] -= g.rc_4.pwm_out; // CW - motor_out[MOT_2] -= g.rc_4.pwm_out; // CW - motor_out[MOT_7] -= g.rc_4.pwm_out; // CW - motor_out[MOT_8] -= g.rc_4.pwm_out; // CW - - - // TODO add stability patch - motor_out[MOT_1] = min(motor_out[MOT_1], out_max); - motor_out[MOT_2] = min(motor_out[MOT_2], out_max); - motor_out[MOT_3] = min(motor_out[MOT_3], out_max); - motor_out[MOT_4] = min(motor_out[MOT_4], out_max); - motor_out[MOT_5] = min(motor_out[MOT_5], out_max); - motor_out[MOT_6] = min(motor_out[MOT_6], out_max); - motor_out[MOT_7] = min(motor_out[MOT_7], out_max); - motor_out[MOT_8] = min(motor_out[MOT_8], out_max); - - - // limit output so motors don't stop - motor_out[MOT_1] = max(motor_out[MOT_1], out_min); - motor_out[MOT_2] = max(motor_out[MOT_2], out_min); - motor_out[MOT_3] = max(motor_out[MOT_3], out_min); - motor_out[MOT_4] = max(motor_out[MOT_4], out_min); - motor_out[MOT_5] = max(motor_out[MOT_5], out_min); - motor_out[MOT_6] = max(motor_out[MOT_6], out_min); - motor_out[MOT_7] = max(motor_out[MOT_7], out_min); - motor_out[MOT_8] = max(motor_out[MOT_8], out_min); - - - #if CUT_MOTORS == ENABLED - // if we are not sending a throttle output, we cut the motors - if(g.rc_3.servo_out == 0){ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - motor_out[MOT_5] = g.rc_3.radio_min; - motor_out[MOT_6] = g.rc_3.radio_min; - motor_out[MOT_7] = g.rc_3.radio_min; - motor_out[MOT_8] = g.rc_3.radio_min; - } - #endif - - // this filter slows the acceleration of motors vs the deceleration - // Idea by Denny Rowland to help with his Yaw issue - for(int8_t m = 1; m <= 8; m++){ - int c = ch_of_mot(m); - if(motor_filtered[c] < motor_out[c]){ - motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2; - }else{ - // don't filter - motor_filtered[c] = motor_out[c]; - } - } - - APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]); - APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]); - APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]); - APM_RC.OutputCh(MOT_7, motor_filtered[MOT_7]); - APM_RC.OutputCh(MOT_8, motor_filtered[MOT_8]); - - #if INSTANT_PWM == 1 - // InstantPWM - APM_RC.Force_Out0_Out1(); - APM_RC.Force_Out2_Out3(); - APM_RC.Force_Out6_Out7(); - #endif -} - -static void output_motors_disarmed() -{ - if(g.rc_3.control_in > 0){ - // we have pushed up the throttle - // remove safety - motor_auto_armed = true; - } - - // fill the motor_out[] array for HIL use - for (unsigned char i = 0; i < 11; i++){ - motor_out[i] = g.rc_3.radio_min; - } - - // Send commands to motors - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_8, g.rc_3.radio_min); - - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_7, g.rc_3.radio_min); -} - -static void output_motor_test() -{ - - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - motor_out[MOT_5] = g.rc_3.radio_min; - motor_out[MOT_6] = g.rc_3.radio_min; - motor_out[MOT_7] = g.rc_3.radio_min; - motor_out[MOT_8] = g.rc_3.radio_min; - - - if(g.frame_orientation == X_FRAME || g.frame_orientation == PLUS_FRAME){ - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - delay(4000); - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_8, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_7, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100); - delay(300); - } - - if(g.frame_orientation == V_FRAME){ - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - delay(4000); - APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_7, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_8, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100); - delay(300); - } - - APM_RC.OutputCh(MOT_1, motor_out[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_out[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_out[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_out[MOT_4]); - APM_RC.OutputCh(MOT_5, motor_out[MOT_5]); - APM_RC.OutputCh(MOT_6, motor_out[MOT_6]); - APM_RC.OutputCh(MOT_7, motor_out[MOT_7]); - APM_RC.OutputCh(MOT_8, motor_out[MOT_8]); - -} - -#endif - diff --git a/ArduCopter/motors_octa_quad.pde b/ArduCopter/motors_octa_quad.pde deleted file mode 100644 index 3032c6d82a..0000000000 --- a/ArduCopter/motors_octa_quad.pde +++ /dev/null @@ -1,227 +0,0 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -#if FRAME_CONFIG == OCTA_QUAD_FRAME - -static void init_motors_out() -{ - #if INSTANT_PWM == 0 - APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4) - | _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8), - g.rc_speed); - #endif -} - -static void motors_output_enable() -{ - APM_RC.enable_out(MOT_1); - APM_RC.enable_out(MOT_2); - APM_RC.enable_out(MOT_3); - APM_RC.enable_out(MOT_4); - APM_RC.enable_out(MOT_5); - APM_RC.enable_out(MOT_6); - APM_RC.enable_out(MOT_7); - APM_RC.enable_out(MOT_8); -} - -static void output_motors_armed() -{ - int roll_out, pitch_out; - int out_min = g.rc_3.radio_min; - int out_max = g.rc_3.radio_max; - - // Throttle is 0 to 1000 only - g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE); - - if(g.rc_3.servo_out > 0) - out_min = g.rc_3.radio_min + MINIMUM_THROTTLE; - - g.rc_1.calc_pwm(); - g.rc_2.calc_pwm(); - g.rc_3.calc_pwm(); - g.rc_4.calc_pwm(); - - if(g.frame_orientation == X_FRAME){ - roll_out = (float)g.rc_1.pwm_out * 0.707; - pitch_out = (float)g.rc_2.pwm_out * 0.707; - - motor_out[MOT_1] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // APM2 OUT1 APM1 OUT1 FRONT RIGHT CCW TOP - motor_out[MOT_2] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // APM2 OUT2 APM1 OUT2 FRONT LEFT CW TOP - motor_out[MOT_3] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out - pitch_out); // APM2 OUT3 APM1 OUT3 BACK LEFT CCW TOP - motor_out[MOT_4] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out - pitch_out); // APM2 OUT4 APM1 OUT4 BACK RIGHT CW TOP - motor_out[MOT_5] = g.rc_3.radio_out + roll_out + pitch_out; // APM2 OUT5 APM1 OUT7 FRONT LEFT CCW BOTTOM - motor_out[MOT_6] = g.rc_3.radio_out - roll_out + pitch_out; // APM2 OUT6 APM1 OUT8 FRONT RIGHT CW BOTTOM - motor_out[MOT_7] = g.rc_3.radio_out - roll_out - pitch_out; // APM2 OUT7 APM1 OUT10 BACK RIGHT CCW BOTTOM - motor_out[MOT_8] = g.rc_3.radio_out + roll_out - pitch_out; // APM2 OUT8 APM1 OUT11 BACK LEFT CW BOTTOM - }else{ - roll_out = g.rc_1.pwm_out; - pitch_out = g.rc_2.pwm_out; - - motor_out[MOT_1] = (g.rc_3.radio_out * g.top_bottom_ratio) + pitch_out; // APM2 OUT1 APM1 OUT1 FRONT CCW TOP - motor_out[MOT_2] = (g.rc_3.radio_out * g.top_bottom_ratio) + roll_out; // APM2 OUT2 APM1 OUT2 LEFT CW TOP - motor_out[MOT_3] = (g.rc_3.radio_out * g.top_bottom_ratio) - pitch_out; // APM2 OUT3 APM1 OUT3 BACK CCW TOP - motor_out[MOT_4] = (g.rc_3.radio_out * g.top_bottom_ratio) - roll_out; // APM2 OUT4 APM1 OUT4 RIGHT CW TOP - motor_out[MOT_5] = g.rc_3.radio_out + roll_out; // APM2 OUT5 APM1 OUT7 LEFT CCW BOTTOM - motor_out[MOT_6] = g.rc_3.radio_out + pitch_out; // APM2 OUT6 APM1 OUT8 FRONT CW BOTTOM - motor_out[MOT_7] = g.rc_3.radio_out - roll_out; // APM2 OUT7 APM1 OUT10 RIGHT CCW BOTTOM - motor_out[MOT_8] = g.rc_3.radio_out - pitch_out; // APM2 OUT8 APM1 OUT11 BACK CW BOTTOM - } - - // Yaw - motor_out[MOT_1] += g.rc_4.pwm_out; // CCW - motor_out[MOT_3] += g.rc_4.pwm_out; // CCW - motor_out[MOT_5] += g.rc_4.pwm_out; // CCW - motor_out[MOT_7] += g.rc_4.pwm_out; // CCW - - motor_out[MOT_2] -= g.rc_4.pwm_out; // CW - motor_out[MOT_4] -= g.rc_4.pwm_out; // CW - motor_out[MOT_6] -= g.rc_4.pwm_out; // CW - motor_out[MOT_8] -= g.rc_4.pwm_out; // CW - - // TODO add stability patch - motor_out[MOT_1] = min(motor_out[MOT_1], out_max); - motor_out[MOT_2] = min(motor_out[MOT_2], out_max); - motor_out[MOT_3] = min(motor_out[MOT_3], out_max); - motor_out[MOT_4] = min(motor_out[MOT_4], out_max); - motor_out[MOT_5] = min(motor_out[MOT_5], out_max); - motor_out[MOT_6] = min(motor_out[MOT_6], out_max); - motor_out[MOT_7] = min(motor_out[MOT_7], out_max); - motor_out[MOT_8] = min(motor_out[MOT_8], out_max); - - // limit output so motors don't stop - motor_out[MOT_1] = max(motor_out[MOT_1], out_min); - motor_out[MOT_2] = max(motor_out[MOT_2], out_min); - motor_out[MOT_3] = max(motor_out[MOT_3], out_min); - motor_out[MOT_4] = max(motor_out[MOT_4], out_min); - motor_out[MOT_5] = max(motor_out[MOT_5], out_min); - motor_out[MOT_6] = max(motor_out[MOT_6], out_min); - motor_out[MOT_7] = max(motor_out[MOT_7], out_min); - motor_out[MOT_8] = max(motor_out[MOT_8], out_min); - - #if CUT_MOTORS == ENABLED - // if we are not sending a throttle output, we cut the motors - if(g.rc_3.servo_out == 0){ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - motor_out[MOT_5] = g.rc_3.radio_min; - motor_out[MOT_6] = g.rc_3.radio_min; - motor_out[MOT_7] = g.rc_3.radio_min; - motor_out[MOT_8] = g.rc_3.radio_min; - } - #endif - - // this filter slows the acceleration of motors vs the deceleration - // Idea by Denny Rowland to help with his Yaw issue - for(int8_t m = 1; m <= 8; m++){ - int i = ch_of_mot(m); - if(motor_filtered[i] < motor_out[i]){ - motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2; - }else{ - // don't filter - motor_filtered[i] = motor_out[i]; - } - } - - APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]); - APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]); - APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]); - APM_RC.OutputCh(MOT_7, motor_filtered[MOT_7]); - APM_RC.OutputCh(MOT_8, motor_filtered[MOT_8]); - - #if INSTANT_PWM == 1 - // InstantPWM - APM_RC.Force_Out0_Out1(); - APM_RC.Force_Out2_Out3(); - APM_RC.Force_Out6_Out7(); - #endif -} - -static void output_motors_disarmed() -{ - if(g.rc_3.control_in > 0){ - // we have pushed up the throttle - // remove safety - motor_auto_armed = true; - } - - // fill the motor_out[] array for HIL use - for (unsigned char i = 0; i < 11; i++){ - motor_out[i] = g.rc_3.radio_min; - } - - // Send commands to motors - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_7, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_8, g.rc_3.radio_min); -} - -static void output_motor_test() -{ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - motor_out[MOT_5] = g.rc_3.radio_min; - motor_out[MOT_6] = g.rc_3.radio_min; - motor_out[MOT_7] = g.rc_3.radio_min; - motor_out[MOT_8] = g.rc_3.radio_min; - - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - delay(5000); - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_7, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_8, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, motor_out[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_out[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_out[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_out[MOT_4]); - APM_RC.OutputCh(MOT_5, motor_out[MOT_5]); - APM_RC.OutputCh(MOT_6, motor_out[MOT_6]); - APM_RC.OutputCh(MOT_7, motor_out[MOT_7]); - APM_RC.OutputCh(MOT_8, motor_out[MOT_8]); -} -#endif diff --git a/ArduCopter/motors_quad.pde b/ArduCopter/motors_quad.pde deleted file mode 100644 index fc50996585..0000000000 --- a/ArduCopter/motors_quad.pde +++ /dev/null @@ -1,209 +0,0 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -#if FRAME_CONFIG == QUAD_FRAME - -static void init_motors_out() -{ - #if INSTANT_PWM == 0 - APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4), - g.rc_speed); - #endif -} - -static void motors_output_enable() -{ - APM_RC.enable_out(MOT_1); - APM_RC.enable_out(MOT_2); - APM_RC.enable_out(MOT_3); - APM_RC.enable_out(MOT_4); -} - -static void output_motors_armed() -{ - int roll_out, pitch_out; - int out_min = g.rc_3.radio_min; - int out_max = g.rc_3.radio_max; - - // Throttle is 0 to 1000 only - g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE); - - if(g.rc_3.servo_out > 0) - out_min = g.rc_3.radio_min + MINIMUM_THROTTLE; - - g.rc_1.calc_pwm(); - g.rc_2.calc_pwm(); - g.rc_3.calc_pwm(); - g.rc_4.calc_pwm(); - - - - if(g.frame_orientation == X_FRAME){ - roll_out = (float)g.rc_1.pwm_out * 0.707; - pitch_out = (float)g.rc_2.pwm_out * 0.707; - - // left - motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // FRONT - motor_out[MOT_2] = g.rc_3.radio_out + roll_out - pitch_out; // BACK - - // right - motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out; // FRONT - motor_out[MOT_4] = g.rc_3.radio_out - roll_out - pitch_out; // BACK - - }else{ - - roll_out = g.rc_1.pwm_out; - pitch_out = g.rc_2.pwm_out; - - // right motor - motor_out[MOT_1] = g.rc_3.radio_out - roll_out; - // left motor - motor_out[MOT_2] = g.rc_3.radio_out + roll_out; - // front motor - motor_out[MOT_3] = g.rc_3.radio_out + pitch_out; - // back motor - motor_out[MOT_4] = g.rc_3.radio_out - pitch_out; - } - - // Yaw input - motor_out[MOT_1] += g.rc_4.pwm_out; // CCW - motor_out[MOT_2] += g.rc_4.pwm_out; // CCW - motor_out[MOT_3] -= g.rc_4.pwm_out; // CW - motor_out[MOT_4] -= g.rc_4.pwm_out; // CW - - /* We need to clip motor output at out_max. When cipping a motors - * output we also need to compensate for the instability by - * lowering the opposite motor by the same proportion. This - * ensures that we retain control when one or more of the motors - * is at its maximum output - */ - for (int i = MOT_1; i <= MOT_4; i++){ - if(motor_out[i] > out_max){ - // note that i^1 is the opposite motor - motor_out[i ^ 1] -= motor_out[i] - out_max; - motor_out[i] = out_max; - } - } - - // limit output so motors don't stop - motor_out[MOT_1] = max(motor_out[MOT_1], out_min); - motor_out[MOT_2] = max(motor_out[MOT_2], out_min); - motor_out[MOT_3] = max(motor_out[MOT_3], out_min); - motor_out[MOT_4] = max(motor_out[MOT_4], out_min); - - #if CUT_MOTORS == ENABLED - // if we are not sending a throttle output, we cut the motors - if(g.rc_3.servo_out == 0){ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - } - #endif - - APM_RC.OutputCh(MOT_1, motor_out[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_out[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_out[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_out[MOT_4]); - - - #if INSTANT_PWM == 1 - // InstantPWM - APM_RC.Force_Out0_Out1(); - APM_RC.Force_Out2_Out3(); - #endif - - //debug_motors(); -} - -static void output_motors_disarmed() -{ - if(g.rc_3.control_in > 0){ - // we have pushed up the throttle - // remove safety - motor_auto_armed = true; - } - - // fill the motor_out[] array for HIL use - for (unsigned char i = 0; i < 8; i++){ - motor_out[i] = g.rc_3.radio_min; - } - - // Send commands to motors - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); -} - -/* -//static void debug_motors() -{ - Serial.printf("1:%d\t2:%d\t3:%d\t4:%d\n", - motor_out[MOT_1], - motor_out[MOT_2], - motor_out[MOT_3], - motor_out[MOT_4]); -} -//*/ - -static void output_motor_test() -{ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - - - if(g.frame_orientation == X_FRAME){ - - APM_RC.OutputCh(MOT_3, g.rc_2.radio_min); - delay(4000); - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_4, g.rc_1.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_1.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_2, g.rc_4.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_2, g.rc_4.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_3, g.rc_2.radio_min + 100); - delay(300); - - }else{ - - APM_RC.OutputCh(MOT_2, g.rc_2.radio_min); - delay(4000); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_1, g.rc_1.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, g.rc_1.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_4, g.rc_4.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_4.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_2, g.rc_2.radio_min + 100); - delay(300); - - } - - APM_RC.OutputCh(MOT_1, motor_out[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_out[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_out[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_out[MOT_4]); -} - -#endif diff --git a/ArduCopter/motors_tri.pde b/ArduCopter/motors_tri.pde deleted file mode 100644 index 9371201557..0000000000 --- a/ArduCopter/motors_tri.pde +++ /dev/null @@ -1,137 +0,0 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#if FRAME_CONFIG == TRI_FRAME - -static void init_motors_out() -{ - #if INSTANT_PWM == 0 - APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_4), - g.rc_speed); - #endif -} - -static void motors_output_enable() -{ - APM_RC.enable_out(MOT_1); - APM_RC.enable_out(MOT_2); - APM_RC.enable_out(MOT_4); - APM_RC.enable_out(CH_TRI_YAW); -} - - -static void output_motors_armed() -{ - int out_min = g.rc_3.radio_min; - int out_max = g.rc_3.radio_max; - - // Throttle is 0 to 1000 only - g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE); - - if(g.rc_3.servo_out > 0) - out_min = g.rc_3.radio_min + MINIMUM_THROTTLE; - - g.rc_1.calc_pwm(); - g.rc_2.calc_pwm(); - g.rc_3.calc_pwm(); - - int roll_out = (float)g.rc_1.pwm_out * .866; - int pitch_out = g.rc_2.pwm_out / 2; - - //left front - motor_out[MOT_2] = g.rc_3.radio_out + roll_out + pitch_out; - //right front - motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out; - // rear - motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out; - - //motor_out[MOT_4] += (float)(abs(g.rc_4.control_in)) * .013; - - // Tridge's stability patch - if(motor_out[MOT_1] > out_max){ - motor_out[MOT_2] -= (motor_out[MOT_1] - out_max) >> 1; - motor_out[MOT_4] -= (motor_out[MOT_1] - out_max) >> 1; - motor_out[MOT_1] = out_max; - } - - if(motor_out[MOT_2] > out_max){ - motor_out[MOT_1] -= (motor_out[MOT_2] - out_max) >> 1; - motor_out[MOT_4] -= (motor_out[MOT_2] - out_max) >> 1; - motor_out[MOT_2] = out_max; - } - - if(motor_out[MOT_4] > out_max){ - motor_out[MOT_1] -= (motor_out[MOT_4] - out_max) >> 1; - motor_out[MOT_2] -= (motor_out[MOT_4] - out_max) >> 1; - motor_out[MOT_4] = out_max; - } - - // limit output so motors don't stop - motor_out[MOT_1] = max(motor_out[MOT_1], out_min); - motor_out[MOT_2] = max(motor_out[MOT_2], out_min); - motor_out[MOT_4] = max(motor_out[MOT_4], out_min); - - #if CUT_MOTORS == ENABLED - // if we are not sending a throttle output, we cut the motors - if(g.rc_3.servo_out == 0){ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - } - #endif - - APM_RC.OutputCh(MOT_1, motor_out[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_out[MOT_2]); - APM_RC.OutputCh(MOT_4, motor_out[MOT_4]); - - #if INSTANT_PWM == 1 - // InstantPWM - APM_RC.Force_Out0_Out1(); - APM_RC.Force_Out2_Out3(); - #endif -} - -static void output_motors_disarmed() -{ - if(g.rc_3.control_in > 0){ - // we have pushed up the throttle - // remove safety - motor_auto_armed = true; - } - - // fill the motor_out[] array for HIL use - for (unsigned char i = 0; i < 8; i++){ - motor_out[i] = g.rc_3.radio_min; - } - - // Send commands to motors - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); -} - -static void output_motor_test() -{ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - - APM_RC.OutputCh(MOT_2, g.rc_2.radio_min); - delay(4000); - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_4, g.rc_1.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_1.radio_min); - delay(2000); - APM_RC.OutputCh(MOT_2, g.rc_4.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, motor_out[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_out[MOT_2]); - APM_RC.OutputCh(MOT_4, motor_out[MOT_4]); -} - -#endif diff --git a/ArduCopter/motors_y6.pde b/ArduCopter/motors_y6.pde deleted file mode 100644 index a86d63ec6a..0000000000 --- a/ArduCopter/motors_y6.pde +++ /dev/null @@ -1,216 +0,0 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -#if FRAME_CONFIG == Y6_FRAME - -#define YAW_DIRECTION 1 - -static void init_motors_out() -{ - #if INSTANT_PWM == 0 - APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4) - | _BV(MOT_5) | _BV(MOT_6), - g.rc_speed); - #endif -} - -static void motors_output_enable() -{ - APM_RC.enable_out(MOT_1); - APM_RC.enable_out(MOT_2); - APM_RC.enable_out(MOT_3); - APM_RC.enable_out(MOT_4); - APM_RC.enable_out(MOT_5); - APM_RC.enable_out(MOT_6); -} - -static void output_motors_armed() -{ - int out_min = g.rc_3.radio_min; - int out_max = g.rc_3.radio_max; - - // Throttle is 0 to 1000 only - g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE); - - if(g.rc_3.servo_out > 0) - out_min = g.rc_3.radio_min + MINIMUM_THROTTLE; - - g.rc_1.calc_pwm(); - g.rc_2.calc_pwm(); - g.rc_3.calc_pwm(); - g.rc_4.calc_pwm(); - - // Multi-Wii Mix - //left - motor_out[MOT_2] = (g.rc_3.radio_out * g.top_bottom_ratio) + g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // LEFT TOP - CW - motor_out[MOT_3] = g.rc_3.radio_out + g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // BOTTOM_LEFT - CCW - //right - motor_out[MOT_5] = (g.rc_3.radio_out * g.top_bottom_ratio) - g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // RIGHT TOP - CW - motor_out[MOT_1] = g.rc_3.radio_out - g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // BOTTOM_RIGHT - CCW - //back - motor_out[MOT_6] = (g.rc_3.radio_out * g.top_bottom_ratio) - (g.rc_2.pwm_out * 4 / 3); // REAR TOP - CCW - motor_out[MOT_4] = g.rc_3.radio_out - (g.rc_2.pwm_out * 4 / 3); // BOTTOM_REAR - CW - - //left - motor_out[MOT_2] -= YAW_DIRECTION * g.rc_4.pwm_out; // LEFT TOP - CW - motor_out[MOT_3] += YAW_DIRECTION * g.rc_4.pwm_out; // LEFT BOTTOM - CCW - //right - motor_out[MOT_5] -= YAW_DIRECTION * g.rc_4.pwm_out; // RIGHT TOP - CW - motor_out[MOT_1] += YAW_DIRECTION * g.rc_4.pwm_out; // RIGHT BOTTOM - CCW - //back - motor_out[MOT_6] += YAW_DIRECTION * g.rc_4.pwm_out; // REAR TOP - CCW - motor_out[MOT_4] -= YAW_DIRECTION * g.rc_4.pwm_out; // REAR BOTTOM - CW - - - /* - int roll_out = (float)g.rc_1.pwm_out * .866; - int pitch_out = g.rc_2.pwm_out / 2; - - //left - motor_out[MOT_2] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // CCW TOP - motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // CW - - //right - motor_out[MOT_5] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // CCW TOP - motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out; // CW - - //back - motor_out[MOT_6] = ((g.rc_3.radio_out * g.top_bottom_ratio) - g.rc_2.pwm_out); // CCW TOP - motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out; // CW - - // Yaw - //top - motor_out[MOT_2] += g.rc_4.pwm_out; // CCW - motor_out[MOT_5] += g.rc_4.pwm_out; // CCW - motor_out[MOT_6] += g.rc_4.pwm_out; // CCW - - //bottom - motor_out[MOT_3] -= g.rc_4.pwm_out; // CW - motor_out[MOT_1] -= g.rc_4.pwm_out; // CW - motor_out[MOT_4] -= g.rc_4.pwm_out; // CW - */ - - // TODO: add stability patch - motor_out[MOT_1] = min(motor_out[MOT_1], out_max); - motor_out[MOT_2] = min(motor_out[MOT_2], out_max); - motor_out[MOT_3] = min(motor_out[MOT_3], out_max); - motor_out[MOT_4] = min(motor_out[MOT_4], out_max); - motor_out[MOT_5] = min(motor_out[MOT_5], out_max); - motor_out[MOT_6] = min(motor_out[MOT_6], out_max); - - // limit output so motors don't stop - motor_out[MOT_1] = max(motor_out[MOT_1], out_min); - motor_out[MOT_2] = max(motor_out[MOT_2], out_min); - motor_out[MOT_3] = max(motor_out[MOT_3], out_min); - motor_out[MOT_4] = max(motor_out[MOT_4], out_min); - motor_out[MOT_5] = max(motor_out[MOT_5], out_min); - motor_out[MOT_6] = max(motor_out[MOT_6], out_min); - - #if CUT_MOTORS == ENABLED - // if we are not sending a throttle output, we cut the motors - if(g.rc_3.servo_out == 0){ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - motor_out[MOT_5] = g.rc_3.radio_min; - motor_out[MOT_6] = g.rc_3.radio_min; - } - #endif - - // this filter slows the acceleration of motors vs the deceleration - // Idea by Denny Rowland to help with his Yaw issue - for(int8_t m = 1; m <= 6; m++){ - int i = ch_of_mot(m); - if(motor_filtered[i] < motor_out[i]){ - motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2; - }else{ - // don't filter - motor_filtered[i] = motor_out[i]; - } - } - - APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]); - APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]); - APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]); - APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]); - - #if INSTANT_PWM == 1 - // InstantPWM - APM_RC.Force_Out0_Out1(); - APM_RC.Force_Out2_Out3(); - APM_RC.Force_Out6_Out7(); - #endif -} - -static void output_motors_disarmed() -{ - if(g.rc_3.control_in > 0){ - // we have pushed up the throttle - // remove safety - motor_auto_armed = true; - } - - // fill the motor_out[] array for HIL use - for (unsigned char i = 0; i < 8; i++){ - motor_out[i] = g.rc_3.radio_min; - } - - // Send commands to motors - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); -} - -static void output_motor_test() -{ - motor_out[MOT_1] = g.rc_3.radio_min; - motor_out[MOT_2] = g.rc_3.radio_min; - motor_out[MOT_3] = g.rc_3.radio_min; - motor_out[MOT_4] = g.rc_3.radio_min; - motor_out[MOT_5] = g.rc_3.radio_min; - motor_out[MOT_6] = g.rc_3.radio_min; - - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); - delay(5000); - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); - delay(3000); - APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); - delay(300); - - APM_RC.OutputCh(MOT_1, motor_out[MOT_1]); - APM_RC.OutputCh(MOT_2, motor_out[MOT_2]); - APM_RC.OutputCh(MOT_3, motor_out[MOT_4]); - APM_RC.OutputCh(MOT_4, motor_out[MOT_4]); - APM_RC.OutputCh(MOT_5, motor_out[MOT_5]); - APM_RC.OutputCh(MOT_6, motor_out[MOT_6]); -} - -#endif