|
|
|
@ -5,8 +5,8 @@
@@ -5,8 +5,8 @@
|
|
|
|
|
static void init_motors_out() |
|
|
|
|
{ |
|
|
|
|
#if INSTANT_PWM == 0 |
|
|
|
|
APM_RC.SetFastOutputChannels( _BV(CH_1) | _BV(CH_2) | _BV(CH_3) | _BV(CH_4) |
|
|
|
|
| _BV(CH_7) | _BV(CH_8) ); |
|
|
|
|
APM_RC.SetFastOutputChannels( _BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4) |
|
|
|
|
| _BV(MOT_5) | _BV(MOT_6) ); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -32,38 +32,38 @@ static void output_motors_armed()
@@ -32,38 +32,38 @@ static void output_motors_armed()
|
|
|
|
|
pitch_out = (float)g.rc_2.pwm_out * .866; |
|
|
|
|
|
|
|
|
|
//left side |
|
|
|
|
motor_out[CH_2] = g.rc_3.radio_out + g.rc_1.pwm_out; // CCW Middle |
|
|
|
|
motor_out[CH_3] = g.rc_3.radio_out + roll_out + pitch_out; // CW Front |
|
|
|
|
motor_out[CH_8] = g.rc_3.radio_out + roll_out - pitch_out; // CW Back |
|
|
|
|
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[CH_1] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW Middle |
|
|
|
|
motor_out[CH_7] = g.rc_3.radio_out - roll_out + pitch_out; // CCW Front |
|
|
|
|
motor_out[CH_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW Back |
|
|
|
|
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[CH_1] = g.rc_3.radio_out + g.rc_2.pwm_out; // CW FRONT |
|
|
|
|
motor_out[CH_7] = g.rc_3.radio_out + roll_out + pitch_out; // CCW FRONT LEFT |
|
|
|
|
motor_out[CH_4] = g.rc_3.radio_out - roll_out + pitch_out; // CCW FRONT RIGHT |
|
|
|
|
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[CH_2] = g.rc_3.radio_out - g.rc_2.pwm_out; // CCW BACK |
|
|
|
|
motor_out[CH_3] = g.rc_3.radio_out + roll_out - pitch_out; // CW, BACK LEFT |
|
|
|
|
motor_out[CH_8] = g.rc_3.radio_out - roll_out - pitch_out; // CW BACK RIGHT |
|
|
|
|
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[CH_2] += g.rc_4.pwm_out; // CCW |
|
|
|
|
motor_out[CH_7] += g.rc_4.pwm_out; // CCW |
|
|
|
|
motor_out[CH_4] += g.rc_4.pwm_out; // CCW |
|
|
|
|
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[CH_3] -= g.rc_4.pwm_out; // CW |
|
|
|
|
motor_out[CH_1] -= g.rc_4.pwm_out; // CW |
|
|
|
|
motor_out[CH_8] -= g.rc_4.pwm_out; // CW |
|
|
|
|
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 |
|
|
|
@ -77,22 +77,22 @@ static void output_motors_armed()
@@ -77,22 +77,22 @@ static void output_motors_armed()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// 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); |
|
|
|
|
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[CH_1] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_2] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_3] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_4] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_7] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_8] = g.rc_3.radio_min; |
|
|
|
|
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 |
|
|
|
|
|
|
|
|
@ -108,12 +108,12 @@ static void output_motors_armed()
@@ -108,12 +108,12 @@ static void output_motors_armed()
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_1, motor_filtered[CH_1]); |
|
|
|
|
APM_RC.OutputCh(CH_2, motor_filtered[CH_2]); |
|
|
|
|
APM_RC.OutputCh(CH_3, motor_filtered[CH_3]); |
|
|
|
|
APM_RC.OutputCh(CH_4, motor_filtered[CH_4]); |
|
|
|
|
APM_RC.OutputCh(CH_7, motor_filtered[CH_7]); |
|
|
|
|
APM_RC.OutputCh(CH_8, motor_filtered[CH_8]); |
|
|
|
|
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 |
|
|
|
@ -138,43 +138,43 @@ static void output_motors_disarmed()
@@ -138,43 +138,43 @@ static void output_motors_disarmed()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Send commands to motors |
|
|
|
|
APM_RC.OutputCh(CH_1, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_2, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_3, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_4, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_7, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_8, g.rc_3.radio_min); |
|
|
|
|
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[CH_1] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_2] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_3] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_4] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_7] = g.rc_3.radio_min; |
|
|
|
|
motor_out[CH_8] = g.rc_3.radio_min; |
|
|
|
|
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){ |
|
|
|
|
// 31 |
|
|
|
|
// 24 |
|
|
|
|
if(g.rc_1.control_in > 3000){ // right |
|
|
|
|
motor_out[CH_1] += 100; |
|
|
|
|
motor_out[MOT_1] += 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.rc_1.control_in < -3000){ // left |
|
|
|
|
motor_out[CH_2] += 100; |
|
|
|
|
motor_out[MOT_2] += 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.rc_2.control_in > 3000){ // back |
|
|
|
|
motor_out[CH_8] += 100; |
|
|
|
|
motor_out[CH_4] += 100; |
|
|
|
|
motor_out[MOT_6] += 100; |
|
|
|
|
motor_out[MOT_4] += 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.rc_2.control_in < -3000){ // front |
|
|
|
|
motor_out[CH_7] += 100; |
|
|
|
|
motor_out[CH_3] += 100; |
|
|
|
|
motor_out[MOT_5] += 100; |
|
|
|
|
motor_out[MOT_3] += 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
}else{ |
|
|
|
@ -182,56 +182,56 @@ static void output_motor_test()
@@ -182,56 +182,56 @@ static void output_motor_test()
|
|
|
|
|
// 2 1 |
|
|
|
|
// 4 |
|
|
|
|
if(g.rc_1.control_in > 3000){ // right |
|
|
|
|
motor_out[CH_4] += 100; |
|
|
|
|
motor_out[CH_8] += 100; |
|
|
|
|
motor_out[MOT_4] += 100; |
|
|
|
|
motor_out[MOT_6] += 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.rc_1.control_in < -3000){ // left |
|
|
|
|
motor_out[CH_7] += 100; |
|
|
|
|
motor_out[CH_3] += 100; |
|
|
|
|
motor_out[MOT_5] += 100; |
|
|
|
|
motor_out[MOT_3] += 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.rc_2.control_in > 3000){ // back |
|
|
|
|
motor_out[CH_2] += 100; |
|
|
|
|
motor_out[MOT_2] += 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if(g.rc_2.control_in < -3000){ // front |
|
|
|
|
motor_out[CH_1] += 100; |
|
|
|
|
motor_out[MOT_1] += 100; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_1, motor_out[CH_1]); |
|
|
|
|
APM_RC.OutputCh(CH_2, motor_out[CH_2]); |
|
|
|
|
APM_RC.OutputCh(CH_3, motor_out[CH_3]); |
|
|
|
|
APM_RC.OutputCh(CH_4, motor_out[CH_4]); |
|
|
|
|
APM_RC.OutputCh(CH_7, motor_out[CH_7]); |
|
|
|
|
APM_RC.OutputCh(CH_8, motor_out[CH_8]); |
|
|
|
|
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(CH_2, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 100); |
|
|
|
|
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100); |
|
|
|
|
delay(1000); |
|
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_3, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 100); |
|
|
|
|
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100); |
|
|
|
|
delay(1000); |
|
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_7, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 100); |
|
|
|
|
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100); |
|
|
|
|
delay(1000); |
|
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_1, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 100); |
|
|
|
|
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100); |
|
|
|
|
delay(1000); |
|
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_4, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 100); |
|
|
|
|
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100); |
|
|
|
|
delay(1000); |
|
|
|
|
|
|
|
|
|
APM_RC.OutputCh(CH_8, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 100); |
|
|
|
|
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); |
|
|
|
|
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100); |
|
|
|
|
delay(1000); |
|
|
|
|
} |
|
|
|
|
*/ |
|
|
|
|