mirror of https://github.com/ArduPilot/ardupilot
ArduCopter motors_octa_quad: rewrite remainder from CH_ macros to MOT_ macros
This commit is contained in:
parent
7f4c994346
commit
73610ddb6c
|
@ -5,8 +5,8 @@
|
||||||
static void init_motors_out()
|
static void init_motors_out()
|
||||||
{
|
{
|
||||||
#if INSTANT_PWM == 0
|
#if INSTANT_PWM == 0
|
||||||
APM_RC.SetFastOutputChannels( _BV(CH_1) | _BV(CH_2) | _BV(CH_3) | _BV(CH_4)
|
APM_RC.SetFastOutputChannels( _BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||||
| _BV(CH_7) | _BV(CH_8) | _BV(CH_10) | _BV(CH_11) );
|
| _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8) );
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -32,20 +32,20 @@ static void output_motors_armed()
|
||||||
pitch_out = (float)g.rc_2.pwm_out * .707;
|
pitch_out = (float)g.rc_2.pwm_out * .707;
|
||||||
|
|
||||||
// Front Left
|
// Front Left
|
||||||
motor_out[CH_7] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // CCW TOP
|
motor_out[MOT_5] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // CCW TOP
|
||||||
motor_out[CH_8] = g.rc_3.radio_out + roll_out + pitch_out; // CW
|
motor_out[MOT_6] = g.rc_3.radio_out + roll_out + pitch_out; // CW
|
||||||
|
|
||||||
// Front Right
|
// Front Right
|
||||||
motor_out[CH_10] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // CCW TOP
|
motor_out[MOT_7] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // CCW TOP
|
||||||
motor_out[CH_11] = g.rc_3.radio_out - roll_out + pitch_out; // CW
|
motor_out[MOT_8] = g.rc_3.radio_out - roll_out + pitch_out; // CW
|
||||||
|
|
||||||
// Back Left
|
// Back Left
|
||||||
motor_out[CH_3] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out - pitch_out); // CCW TOP
|
motor_out[MOT_3] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out - pitch_out); // CCW TOP
|
||||||
motor_out[CH_4] = g.rc_3.radio_out + roll_out - pitch_out; // CW
|
motor_out[MOT_4] = g.rc_3.radio_out + roll_out - pitch_out; // CW
|
||||||
|
|
||||||
// Back Right
|
// Back Right
|
||||||
motor_out[CH_1] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out - pitch_out); // CCW TOP
|
motor_out[MOT_1] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out - pitch_out); // CCW TOP
|
||||||
motor_out[CH_2] = g.rc_3.radio_out - roll_out - pitch_out; // CW
|
motor_out[MOT_2] = g.rc_3.radio_out - roll_out - pitch_out; // CW
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -54,71 +54,71 @@ static void output_motors_armed()
|
||||||
pitch_out = g.rc_2.pwm_out;
|
pitch_out = g.rc_2.pwm_out;
|
||||||
|
|
||||||
// Left
|
// Left
|
||||||
motor_out[CH_7] = (g.rc_3.radio_out * g.top_bottom_ratio) - roll_out; // CCW TOP
|
motor_out[MOT_5] = (g.rc_3.radio_out * g.top_bottom_ratio) - roll_out; // CCW TOP
|
||||||
motor_out[CH_8] = g.rc_3.radio_out - roll_out; // CW
|
motor_out[MOT_6] = g.rc_3.radio_out - roll_out; // CW
|
||||||
|
|
||||||
// Right
|
// Right
|
||||||
motor_out[CH_1] = (g.rc_3.radio_out * g.top_bottom_ratio) + roll_out; // CCW TOP
|
motor_out[MOT_1] = (g.rc_3.radio_out * g.top_bottom_ratio) + roll_out; // CCW TOP
|
||||||
motor_out[CH_2] = g.rc_3.radio_out + roll_out; // CW
|
motor_out[MOT_2] = g.rc_3.radio_out + roll_out; // CW
|
||||||
|
|
||||||
// Front
|
// Front
|
||||||
motor_out[CH_10] = (g.rc_3.radio_out * g.top_bottom_ratio) + pitch_out; // CCW TOP
|
motor_out[MOT_7] = (g.rc_3.radio_out * g.top_bottom_ratio) + pitch_out; // CCW TOP
|
||||||
motor_out[CH_11] = g.rc_3.radio_out + pitch_out; // CW
|
motor_out[MOT_8] = g.rc_3.radio_out + pitch_out; // CW
|
||||||
|
|
||||||
// Back
|
// Back
|
||||||
motor_out[CH_3] = (g.rc_3.radio_out * g.top_bottom_ratio) - pitch_out; // CCW TOP
|
motor_out[MOT_3] = (g.rc_3.radio_out * g.top_bottom_ratio) - pitch_out; // CCW TOP
|
||||||
motor_out[CH_4] = g.rc_3.radio_out - pitch_out; // CW
|
motor_out[MOT_4] = g.rc_3.radio_out - pitch_out; // CW
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Yaw
|
// Yaw
|
||||||
motor_out[CH_1] += g.rc_4.pwm_out; // CCW
|
motor_out[MOT_1] += g.rc_4.pwm_out; // CCW
|
||||||
motor_out[CH_3] += g.rc_4.pwm_out; // CCW
|
motor_out[MOT_3] += g.rc_4.pwm_out; // CCW
|
||||||
motor_out[CH_7] += g.rc_4.pwm_out; // CCW
|
motor_out[MOT_5] += g.rc_4.pwm_out; // CCW
|
||||||
motor_out[CH_10] += g.rc_4.pwm_out; // CCW
|
motor_out[MOT_7] += g.rc_4.pwm_out; // CCW
|
||||||
|
|
||||||
motor_out[CH_2] -= g.rc_4.pwm_out; // CW
|
motor_out[MOT_2] -= g.rc_4.pwm_out; // CW
|
||||||
motor_out[CH_4] -= g.rc_4.pwm_out; // CW
|
motor_out[MOT_4] -= g.rc_4.pwm_out; // CW
|
||||||
motor_out[CH_8] -= g.rc_4.pwm_out; // CW
|
motor_out[MOT_6] -= g.rc_4.pwm_out; // CW
|
||||||
motor_out[CH_11] -= g.rc_4.pwm_out; // CW
|
motor_out[MOT_8] -= g.rc_4.pwm_out; // CW
|
||||||
|
|
||||||
// TODO add stability patch
|
// TODO add stability patch
|
||||||
motor_out[CH_1] = min(motor_out[CH_1], out_max);
|
motor_out[MOT_1] = min(motor_out[MOT_1], out_max);
|
||||||
motor_out[CH_2] = min(motor_out[CH_2], out_max);
|
motor_out[MOT_2] = min(motor_out[MOT_2], out_max);
|
||||||
motor_out[CH_3] = min(motor_out[CH_3], out_max);
|
motor_out[MOT_3] = min(motor_out[MOT_3], out_max);
|
||||||
motor_out[CH_4] = min(motor_out[CH_4], out_max);
|
motor_out[MOT_4] = min(motor_out[MOT_4], out_max);
|
||||||
motor_out[CH_7] = min(motor_out[CH_7], out_max);
|
motor_out[MOT_5] = min(motor_out[MOT_5], out_max);
|
||||||
motor_out[CH_8] = min(motor_out[CH_8], out_max);
|
motor_out[MOT_6] = min(motor_out[MOT_6], out_max);
|
||||||
motor_out[CH_10] = min(motor_out[CH_10], out_max);
|
motor_out[MOT_7] = min(motor_out[MOT_7], out_max);
|
||||||
motor_out[CH_11] = min(motor_out[CH_11], out_max);
|
motor_out[MOT_8] = min(motor_out[MOT_8], out_max);
|
||||||
|
|
||||||
// limit output so motors don't stop
|
// limit output so motors don't stop
|
||||||
motor_out[CH_1] = max(motor_out[CH_1], out_min);
|
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||||
motor_out[CH_2] = max(motor_out[CH_2], out_min);
|
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||||
motor_out[CH_3] = max(motor_out[CH_3], out_min);
|
motor_out[MOT_3] = max(motor_out[MOT_3], out_min);
|
||||||
motor_out[CH_4] = max(motor_out[CH_4], out_min);
|
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||||
motor_out[CH_7] = max(motor_out[CH_7], out_min);
|
motor_out[MOT_5] = max(motor_out[MOT_5], out_min);
|
||||||
motor_out[CH_8] = max(motor_out[CH_8], out_min);
|
motor_out[MOT_6] = max(motor_out[MOT_6], out_min);
|
||||||
motor_out[CH_10] = max(motor_out[CH_10], out_min);
|
motor_out[MOT_7] = max(motor_out[MOT_7], out_min);
|
||||||
motor_out[CH_11] = max(motor_out[CH_11], out_min);
|
motor_out[MOT_8] = max(motor_out[MOT_8], out_min);
|
||||||
|
|
||||||
#if CUT_MOTORS == ENABLED
|
#if CUT_MOTORS == ENABLED
|
||||||
// if we are not sending a throttle output, we cut the motors
|
// if we are not sending a throttle output, we cut the motors
|
||||||
if(g.rc_3.servo_out == 0){
|
if(g.rc_3.servo_out == 0){
|
||||||
motor_out[CH_1] = g.rc_3.radio_min;
|
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||||
motor_out[CH_2] = g.rc_3.radio_min;
|
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||||
motor_out[CH_3] = g.rc_3.radio_min;
|
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||||
motor_out[CH_4] = g.rc_3.radio_min;
|
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||||
motor_out[CH_7] = g.rc_3.radio_min;
|
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||||
motor_out[CH_8] = g.rc_3.radio_min;
|
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||||
motor_out[CH_10] = g.rc_3.radio_min;
|
motor_out[MOT_7] = g.rc_3.radio_min;
|
||||||
motor_out[CH_11] = g.rc_3.radio_min;
|
motor_out[MOT_8] = g.rc_3.radio_min;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// this filter slows the acceleration of motors vs the deceleration
|
// this filter slows the acceleration of motors vs the deceleration
|
||||||
// Idea by Denny Rowland to help with his Yaw issue
|
// Idea by Denny Rowland to help with his Yaw issue
|
||||||
for(int8_t m = 0; i <= 8; m++ ) {
|
for(int8_t m = 0; m <= 8; m++ ) {
|
||||||
int i = ch_of_mot(m);
|
int i = ch_of_mot(m);
|
||||||
if(motor_filtered[i] < motor_out[i]){
|
if(motor_filtered[i] < motor_out[i]){
|
||||||
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
||||||
|
@ -128,14 +128,14 @@ static void output_motors_armed()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_1, motor_filtered[CH_1]);
|
APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
|
||||||
APM_RC.OutputCh(CH_2, motor_filtered[CH_2]);
|
APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
|
||||||
APM_RC.OutputCh(CH_3, motor_filtered[CH_3]);
|
APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
|
||||||
APM_RC.OutputCh(CH_4, motor_filtered[CH_4]);
|
APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
|
||||||
APM_RC.OutputCh(CH_7, motor_filtered[CH_7]);
|
APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
|
||||||
APM_RC.OutputCh(CH_8, motor_filtered[CH_8]);
|
APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
|
||||||
APM_RC.OutputCh(CH_10, motor_filtered[CH_10]);
|
APM_RC.OutputCh(MOT_7, motor_filtered[MOT_7]);
|
||||||
APM_RC.OutputCh(CH_11, motor_filtered[CH_11]);
|
APM_RC.OutputCh(MOT_8, motor_filtered[MOT_8]);
|
||||||
|
|
||||||
#if INSTANT_PWM == 1
|
#if INSTANT_PWM == 1
|
||||||
// InstantPWM
|
// InstantPWM
|
||||||
|
@ -159,48 +159,48 @@ static void output_motors_disarmed()
|
||||||
}
|
}
|
||||||
|
|
||||||
// Send commands to motors
|
// Send commands to motors
|
||||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void output_motor_test()
|
static void output_motor_test()
|
||||||
{
|
{
|
||||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min + 100);
|
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min + 100);
|
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 100);
|
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 100);
|
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 100);
|
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 100);
|
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 100);
|
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
|
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||||
APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 100);
|
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue