motors_quad: translate from CH_ to MOT_ notation.

This commit is contained in:
Pat Hickey 2012-01-01 15:10:20 -05:00
parent 0b40f55334
commit e0e430895e

View File

@ -5,7 +5,7 @@
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) );
#endif #endif
} }
@ -33,12 +33,12 @@ static void output_motors_armed()
pitch_out = g.rc_2.pwm_out * .707; pitch_out = g.rc_2.pwm_out * .707;
// left // left
motor_out[CH_3] = g.rc_3.radio_out + roll_out + pitch_out; // FRONT motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // FRONT
motor_out[CH_2] = g.rc_3.radio_out + roll_out - pitch_out; // BACK motor_out[MOT_2] = g.rc_3.radio_out + roll_out - pitch_out; // BACK
// right // right
motor_out[CH_1] = g.rc_3.radio_out - roll_out + pitch_out; // FRONT motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out; // FRONT
motor_out[CH_4] = g.rc_3.radio_out - roll_out - pitch_out; // BACK motor_out[MOT_4] = g.rc_3.radio_out - roll_out - pitch_out; // BACK
}else{ }else{
@ -46,20 +46,20 @@ static void output_motors_armed()
pitch_out = g.rc_2.pwm_out; pitch_out = g.rc_2.pwm_out;
// right motor // right motor
motor_out[CH_1] = g.rc_3.radio_out - roll_out; motor_out[MOT_1] = g.rc_3.radio_out - roll_out;
// left motor // left motor
motor_out[CH_2] = g.rc_3.radio_out + roll_out; motor_out[MOT_2] = g.rc_3.radio_out + roll_out;
// front motor // front motor
motor_out[CH_3] = g.rc_3.radio_out + pitch_out; motor_out[MOT_3] = g.rc_3.radio_out + pitch_out;
// back motor // back motor
motor_out[CH_4] = g.rc_3.radio_out - pitch_out; motor_out[MOT_4] = g.rc_3.radio_out - pitch_out;
} }
// Yaw input // Yaw input
motor_out[CH_1] += g.rc_4.pwm_out; // CCW motor_out[MOT_1] += g.rc_4.pwm_out; // CCW
motor_out[CH_2] += g.rc_4.pwm_out; // CCW motor_out[MOT_2] += g.rc_4.pwm_out; // CCW
motor_out[CH_3] -= g.rc_4.pwm_out; // CW motor_out[MOT_3] -= 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
/* We need to clip motor output at out_max. When cipping a motors /* We need to clip motor output at out_max. When cipping a motors
* output we also need to compensate for the instability by * output we also need to compensate for the instability by
@ -67,7 +67,7 @@ static void output_motors_armed()
* ensures that we retain control when one or more of the motors * ensures that we retain control when one or more of the motors
* is at its maximum output * is at its maximum output
*/ */
for (int i=CH_1; i<=CH_4; i++) { for (int i=MOT_1; i<=MOT_4; i++) {
if (motor_out[i] > out_max) { if (motor_out[i] > out_max) {
// note that i^1 is the opposite motor // note that i^1 is the opposite motor
motor_out[i^1] -= motor_out[i] - out_max; motor_out[i^1] -= motor_out[i] - out_max;
@ -76,24 +76,24 @@ static void output_motors_armed()
} }
// 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);
#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;
} }
#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 i=CH_1; i <= CH_4; i++ ) { for(int8_t i=MOT_1; i <= MOT_4; i++ ) {
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;
}else{ }else{
@ -102,10 +102,10 @@ 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]);
#if INSTANT_PWM == 1 #if INSTANT_PWM == 1
// InstantPWM // InstantPWM
@ -130,52 +130,52 @@ 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);
} }
/* /*
//static void debug_motors() //static void debug_motors()
{ {
Serial.printf("1:%d\t2:%d\t3:%d\t4:%d\n", Serial.printf("1:%d\t2:%d\t3:%d\t4:%d\n",
motor_out[CH_1], motor_out[MOT_1],
motor_out[CH_2], motor_out[MOT_2],
motor_out[CH_3], motor_out[MOT_3],
motor_out[CH_4]); motor_out[MOT_4]);
} }
//*/ //*/
static void output_motor_test() static void output_motor_test()
{ {
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;
if(g.frame_orientation == X_FRAME){ if(g.frame_orientation == X_FRAME){
// 31 // 31
// 24 // 24
if(g.rc_1.control_in > 3000){ if(g.rc_1.control_in > 3000){
motor_out[CH_1] += 100; motor_out[MOT_1] += 100;
motor_out[CH_4] += 100; motor_out[MOT_4] += 100;
} }
if(g.rc_1.control_in < -3000){ if(g.rc_1.control_in < -3000){
motor_out[CH_2] += 100; motor_out[MOT_2] += 100;
motor_out[CH_3] += 100; motor_out[MOT_3] += 100;
} }
if(g.rc_2.control_in > 3000){ if(g.rc_2.control_in > 3000){
motor_out[CH_2] += 100; motor_out[MOT_2] += 100;
motor_out[CH_4] += 100; motor_out[MOT_4] += 100;
} }
if(g.rc_2.control_in < -3000){ if(g.rc_2.control_in < -3000){
motor_out[CH_1] += 100; motor_out[MOT_1] += 100;
motor_out[CH_3] += 100; motor_out[MOT_3] += 100;
} }
}else{ }else{
@ -183,22 +183,22 @@ static void output_motor_test()
// 2 1 // 2 1
// 4 // 4
if(g.rc_1.control_in > 3000) if(g.rc_1.control_in > 3000)
motor_out[CH_1] += 100; motor_out[MOT_1] += 100;
if(g.rc_1.control_in < -3000) if(g.rc_1.control_in < -3000)
motor_out[CH_2] += 100; motor_out[MOT_2] += 100;
if(g.rc_2.control_in > 3000) if(g.rc_2.control_in > 3000)
motor_out[CH_4] += 100; motor_out[MOT_4] += 100;
if(g.rc_2.control_in < -3000) if(g.rc_2.control_in < -3000)
motor_out[CH_3] += 100; motor_out[MOT_3] += 100;
} }
APM_RC.OutputCh(CH_1, motor_out[CH_1]); APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]); APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]); APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]); APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
} }
#endif #endif