mirror of https://github.com/ArduPilot/ardupilot
AP_ICEngine: add note about ICE_STARTCHN_MIN param
This commit is contained in:
parent
7e79999b86
commit
0ffa83b2dd
|
@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
|||
|
||||
// @Param: START_CHAN
|
||||
// @DisplayName: Input channel for engine start
|
||||
// @Description: This is an RC input channel for requesting engine start. Engine will try to start when channel is at or above 1700. Engine will stop when channel is at or below 1300. Between 1301 and 1699 the engine will not change state unless a MAVLink command or mission item commands a state change, or the vehicle is disamed.
|
||||
// @Description: This is an RC input channel for requesting engine start. Engine will try to start when channel is at or above 1700. Engine will stop when channel is at or below 1300. Between 1301 and 1699 the engine will not change state unless a MAVLink command or mission item commands a state change, or the vehicle is disamed. See ICE_STARTCHN_MIN parameter to change engine stop PWM value and/or to enable debouncing of the START_CH to avoid accidental engine kills due to noise on channel.
|
||||
// @User: Standard
|
||||
// @Values: 0:None,1:Chan1,2:Chan2,3:Chan3,4:Chan4,5:Chan5,6:Chan6,7:Chan7,8:Chan8,9:Chan9,10:Chan10,11:Chan11,12:Chan12,13:Chan13,14:Chan14,15:Chan15,16:Chan16
|
||||
AP_GROUPINFO("START_CHAN", 1, AP_ICEngine, start_chan, 0),
|
||||
|
|
Loading…
Reference in New Issue