mirror of https://github.com/ArduPilot/ardupilot
Copter: Tradheli support for turbine start
This commit is contained in:
parent
20f1d0c4da
commit
84bf3fb74e
|
@ -557,6 +557,7 @@ private:
|
|||
uint8_t inverted_flight : 1; // 1 // true for inverted flight mode
|
||||
uint8_t in_autorotation : 1; // 2 // true when heli is in autorotation
|
||||
bool coll_stk_low ; // 3 // true when collective stick is on lower limit
|
||||
uint8_t start_engine : 1; //3 //true for turbine start condition
|
||||
} heli_flags_t;
|
||||
heli_flags_t heli_flags;
|
||||
|
||||
|
|
|
@ -102,6 +102,7 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxS
|
|||
case AUX_FUNC::TURTLE:
|
||||
case AUX_FUNC::SIMPLE_HEADING_RESET:
|
||||
case AUX_FUNC::ARMDISARM_AIRMODE:
|
||||
case AUX_FUNC::TURB_START:
|
||||
break;
|
||||
case AUX_FUNC::ACRO_TRAINER:
|
||||
case AUX_FUNC::ATTCON_ACCEL_LIM:
|
||||
|
@ -360,7 +361,24 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi
|
|||
copter.ap.motor_interlock_switch = (ch_flag == AuxSwitchPos::HIGH || ch_flag == AuxSwitchPos::MIDDLE);
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
||||
case AUX_FUNC::TURB_START:
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
||||
switch (ch_flag) {
|
||||
case AuxSwitchPos::HIGH:
|
||||
copter.motors->set_turb_start(true);
|
||||
|
||||
break;
|
||||
case AuxSwitchPos::MIDDLE:
|
||||
// nothing
|
||||
break;
|
||||
case AuxSwitchPos::LOW:
|
||||
copter.motors->set_turb_start(false);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
case AUX_FUNC::BRAKE:
|
||||
#if MODE_BRAKE_ENABLED == ENABLED
|
||||
do_aux_function_change_mode(Mode::Number::BRAKE, ch_flag);
|
||||
|
|
Loading…
Reference in New Issue