mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
2.0.39
New hex a motors_out with Tridge's stability patch. Simplified the CUT_MOTORS section of the code. git-svn-id: https://arducopter.googlecode.com/svn/trunk@3024 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
04e05604a5
commit
e7a87006b0
@ -57,6 +57,18 @@ static void output_motors_armed()
|
||||
motor_out[CH_1] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[CH_8] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
|
||||
// Tridge's stability patch
|
||||
for (int i = CH_1; i<=CH_8; i++) {
|
||||
if(i == CH_5 || i == CH_6)
|
||||
break;
|
||||
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[CH_1] = max(motor_out[CH_1], out_min);
|
||||
motor_out[CH_2] = max(motor_out[CH_2], out_min);
|
||||
@ -65,51 +77,29 @@ static void output_motors_armed()
|
||||
motor_out[CH_7] = max(motor_out[CH_7], out_min);
|
||||
motor_out[CH_8] = max(motor_out[CH_8], out_min);
|
||||
|
||||
motor_out[CH_1] = min(motor_out[CH_1], out_max);
|
||||
motor_out[CH_2] = min(motor_out[CH_2], out_max);
|
||||
motor_out[CH_3] = min(motor_out[CH_3], out_max);
|
||||
motor_out[CH_4] = min(motor_out[CH_4], out_max);
|
||||
motor_out[CH_7] = min(motor_out[CH_7], out_max);
|
||||
motor_out[CH_8] = min(motor_out[CH_8], out_max);
|
||||
|
||||
|
||||
#if CUT_MOTORS == ENABLED
|
||||
// Send commands to motors
|
||||
if(g.rc_3.servo_out > 0){
|
||||
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]);
|
||||
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out6_Out7();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
}else{
|
||||
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);
|
||||
// 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;
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
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]);
|
||||
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out6_Out7();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
#endif
|
||||
|
||||
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]);
|
||||
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out6_Out7();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
}
|
||||
|
||||
static void output_motors_disarmed()
|
||||
|
Loading…
Reference in New Issue
Block a user