diff --git a/src/drivers/camera_trigger/camera_trigger_params.c b/src/drivers/camera_trigger/camera_trigger_params.c index 482f584cf1..660bf99e36 100644 --- a/src/drivers/camera_trigger/camera_trigger_params.c +++ b/src/drivers/camera_trigger/camera_trigger_params.c @@ -130,15 +130,18 @@ PARAM_DEFINE_INT32(TRIG_MODE, 0); /** * Camera trigger pin * - * 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 + * Selects which FMU pin is used (range: AUX1-AUX8 on Pixhawk controllers with an I/O board, + * MAIN1-MAIN8 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. * In GPIO mode the delay pin to pin is < .2 uS. * + * Note: only with a value of 56 or 78 it is possible to use the lower pins for + * actuator outputs (e.g. ESC's). + * * @min 1 - * @max 123456 + * @max 12345678 * @decimal 0 * @reboot_required true * @group Camera trigger