mirror of https://github.com/ArduPilot/ardupilot
TradHeli: Creating Flybar Acro mode.
This commit is contained in:
parent
6c0b7b7f53
commit
e1d6103045
|
@ -1640,9 +1640,19 @@ void update_roll_pitch_mode(void)
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
// ACRO does not get SIMPLE mode ability
|
// ACRO does not get SIMPLE mode ability
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
if (motors.flyarbar_mode == 1){
|
||||||
|
g.rc_1.servo_out = g.rc_1.control_in;
|
||||||
|
g.rc_2.servo_out = g.rc_2.control_in;
|
||||||
|
} else {
|
||||||
g.rc_1.servo_out = get_acro_roll(g.rc_1.control_in);
|
g.rc_1.servo_out = get_acro_roll(g.rc_1.control_in);
|
||||||
g.rc_2.servo_out = get_acro_pitch(g.rc_2.control_in);
|
g.rc_2.servo_out = get_acro_pitch(g.rc_2.control_in);
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
g.rc_1.servo_out = get_acro_roll(g.rc_1.control_in);
|
||||||
|
g.rc_2.servo_out = get_acro_pitch(g.rc_2.control_in);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case ROLL_PITCH_STABLE:
|
case ROLL_PITCH_STABLE:
|
||||||
|
|
|
@ -39,6 +39,10 @@
|
||||||
#define AP_MOTORSHELI_RSC_MODE_CH8_PASSTHROUGH 1
|
#define AP_MOTORSHELI_RSC_MODE_CH8_PASSTHROUGH 1
|
||||||
#define AP_MOTORSHELI_RSC_MODE_EXT_GOV 2
|
#define AP_MOTORSHELI_RSC_MODE_EXT_GOV 2
|
||||||
|
|
||||||
|
// head definitions
|
||||||
|
#define FLYBARLESS_HEAD 0
|
||||||
|
#define FLYBAR_HEAD 1
|
||||||
|
|
||||||
|
|
||||||
class AP_HeliControls;
|
class AP_HeliControls;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue