TRIG_PINS: clarify TRIG_PINS on FMU (#12714)

This commit is contained in:
Hamish Willee
2019-08-19 22:45:59 +10:00
committed by Beat Küng
parent 1958275495
commit c1c253d9be
@@ -112,8 +112,8 @@ PARAM_DEFINE_INT32(TRIG_MODE, 0);
/**
* Camera trigger pin
*
* Selects which pin is used, ranges from 1 to 6 (AUX1-AUX6 on px4_fmu-v2 and the rail
* pins on px4_fmu-v4). The PWM interface takes two pins per camera, while relay
* Selects which FMU pin is used (range: AUX1-AUX6 on Pixhawk controllers with an I/O board,
* MAIN1-MAIN6 on controllers without an I/O board. The PWM interface takes two pins per camera, while relay
* triggers on every pin individually. Example: Value 56 would trigger on pins 5 and 6.
* For GPIO mode Pin 6 will be triggered followed by 5. With a value of 65 pin 5 will
* be triggered followed by 6. Pins may be non contiguous. I.E. 16 or 61.