mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
HEXA_P frame support
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2243 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
1b815410c6
commit
f0924a9f1b
@ -157,6 +157,29 @@ set_servos_4()
|
||||
motor_out[CH_1] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[CH_8] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
}else if (g.frame_type == HEXAP_FRAME) {
|
||||
//Serial.println("HEXAP_FRAME");
|
||||
int roll_out = g.rc_1.pwm_out;
|
||||
int pitch_out = (float)g.rc_2.pwm_out * .5;
|
||||
|
||||
//Back side
|
||||
motor_out[CH_8] = g.rc_3.radio_out - g.rc_2.pwm_out; // CCW
|
||||
motor_out[CH_1] = g.rc_3.radio_out + roll_out - pitch_out; // CW
|
||||
motor_out[CH_3] = g.rc_3.radio_out - roll_out - pitch_out; // CW
|
||||
|
||||
//Front side
|
||||
motor_out[CH_7] = g.rc_3.radio_out + g.rc_2.pwm_out; // CW
|
||||
motor_out[CH_2] = g.rc_3.radio_out + roll_out + pitch_out; // CCW
|
||||
motor_out[CH_4] = g.rc_3.radio_out - roll_out + pitch_out; // CCW
|
||||
|
||||
motor_out[CH_8] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[CH_2] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[CH_4] += g.rc_4.pwm_out; // CCW
|
||||
|
||||
motor_out[CH_1] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[CH_7] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[CH_3] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
}else if (g.frame_type == Y6_FRAME) {
|
||||
//Serial.println("Y6_FRAME");
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user