mirror of https://github.com/ArduPilot/ardupilot
ArduCopter motors_tri: rewrite CH_ macros with MOT_ macros
* Third Tricopter motor was on CH_4, so it is called MOT_4. This will be changed in a subsequent commit.
This commit is contained in:
parent
73610ddb6c
commit
ac7f6a5602
|
@ -4,7 +4,7 @@
|
|||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels( _BV(CH_1) | _BV(CH_2) | _BV(CH_4) );
|
||||
APM_RC.SetFastOutputChannels( _BV(MOT_1) | _BV(MOT_2) | _BV(MOT_4) );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -28,50 +28,50 @@ static void output_motors_armed()
|
|||
int pitch_out = g.rc_2.pwm_out / 2;
|
||||
|
||||
//left front
|
||||
motor_out[CH_2] = g.rc_3.radio_out + roll_out + pitch_out;
|
||||
motor_out[MOT_2] = g.rc_3.radio_out + roll_out + pitch_out;
|
||||
//right front
|
||||
motor_out[CH_1] = g.rc_3.radio_out - roll_out + pitch_out;
|
||||
motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out;
|
||||
// rear
|
||||
motor_out[CH_4] = g.rc_3.radio_out - g.rc_2.pwm_out;
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out;
|
||||
|
||||
//motor_out[CH_4] += (float)(abs(g.rc_4.control_in)) * .013;
|
||||
//motor_out[MOT_4] += (float)(abs(g.rc_4.control_in)) * .013;
|
||||
|
||||
// Tridge's stability patch
|
||||
if (motor_out[CH_1] > out_max) {
|
||||
motor_out[CH_2] -= (motor_out[CH_1] - out_max) >> 1;
|
||||
motor_out[CH_4] -= (motor_out[CH_1] - out_max) >> 1;
|
||||
motor_out[CH_1] = out_max;
|
||||
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[CH_2] > out_max) {
|
||||
motor_out[CH_1] -= (motor_out[CH_2] - out_max) >> 1;
|
||||
motor_out[CH_4] -= (motor_out[CH_2] - out_max) >> 1;
|
||||
motor_out[CH_2] = 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[CH_4] > out_max) {
|
||||
motor_out[CH_1] -= (motor_out[CH_4] - out_max) >> 1;
|
||||
motor_out[CH_2] -= (motor_out[CH_4] - out_max) >> 1;
|
||||
motor_out[CH_4] = 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[CH_1] = max(motor_out[CH_1], out_min);
|
||||
motor_out[CH_2] = max(motor_out[CH_2], out_min);
|
||||
motor_out[CH_4] = max(motor_out[CH_4], 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_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[CH_1] = g.rc_3.radio_min;
|
||||
motor_out[CH_2] = g.rc_3.radio_min;
|
||||
motor_out[CH_4] = 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_4] = g.rc_3.radio_min;
|
||||
}
|
||||
#endif
|
||||
|
||||
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
|
||||
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
|
||||
APM_RC.OutputCh(CH_4, motor_out[CH_4]);
|
||||
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
|
||||
|
@ -94,33 +94,33 @@ 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_4, 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_4, 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_4] = 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_4] = g.rc_3.radio_min;
|
||||
|
||||
|
||||
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_4] += 100;
|
||||
motor_out[MOT_4] += 100;
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
|
||||
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
|
||||
APM_RC.OutputCh(CH_4, motor_out[CH_4]);
|
||||
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
|
||||
|
|
Loading…
Reference in New Issue