mirror of https://github.com/ArduPilot/ardupilot
AC_Sprayer: move Copter CHn_OPT to RC_Channel RCn_OPTION
This commit is contained in:
parent
fb786b8d56
commit
007434cdac
|
@ -3,9 +3,9 @@
|
|||
|
||||
/**
|
||||
The crop spraying functionality can be enabled in ArduCopter by doing the following:
|
||||
- set CH7_OPT or CH8_OPT parameter to 15 to allow turning the sprayer on/off from one of these channels
|
||||
- set RC10_FUNCTION to 22 to enable the servo output controlling the pump speed on servo-out 10
|
||||
- set RC11_FUNCTION to 23 to enable the servo output controlling the spinner on servo-out 11
|
||||
- set RC7_OPTION or RC8_OPTION parameter to 15 to allow turning the sprayer on/off from one of these channels
|
||||
- set SERVO10_FUNCTION to 22 to enable the servo output controlling the pump speed on servo-out 10
|
||||
- set SERVO11_FUNCTION to 23 to enable the servo output controlling the spinner on servo-out 11
|
||||
- ensure the RC10_MIN, RC10_MAX, RC11_MIN, RC11_MAX accurately hold the min and maximum servo values you could possibly output to the pump and spinner
|
||||
- set the SPRAY_SPINNER to the pwm value the spinner should spin at when on
|
||||
- set the SPRAY_PUMP_RATE to the value the pump servo should move to when the vehicle is travelling 1m/s expressed as a percentage (i.e. 0 ~ 100) of the full servo range. I.e. 0 = the pump will not operate, 100 = maximum speed at 1m/s. 50 = 1/2 speed at 1m/s, full speed at 2m/s
|
||||
|
|
Loading…
Reference in New Issue