forked from Archive/PX4-Autopilot
Improve trigger meta
This commit is contained in:
parent
a01cb1d0b8
commit
5bcdfed203
|
@ -49,6 +49,7 @@
|
|||
* @unit ms
|
||||
* @min 4.0
|
||||
* @max 10000.0
|
||||
* @decimal 1
|
||||
* @group Camera trigger
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(TRIG_INTERVAL, 40.0f);
|
||||
|
@ -56,10 +57,10 @@ PARAM_DEFINE_FLOAT(TRIG_INTERVAL, 40.0f);
|
|||
/**
|
||||
* Camera trigger polarity
|
||||
*
|
||||
* This parameter sets the polarity of the trigger (0 = ACTIVE_LOW, 1 = ACTIVE_HIGH )
|
||||
* This parameter sets the polarity of the trigger (0 = active low, 1 = active high )
|
||||
*
|
||||
* @value 0 ACTIVE_LOW
|
||||
* @value 1 ACTIVE_HIGH
|
||||
* @value 0 Active low
|
||||
* @value 1 Active high
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @group Camera trigger
|
||||
|
@ -72,6 +73,9 @@ PARAM_DEFINE_INT32(TRIG_POLARITY, 0);
|
|||
* This parameter sets the time the trigger needs to pulled high or low.
|
||||
*
|
||||
* @unit ms
|
||||
* @min 0.1
|
||||
* @max 3
|
||||
* @decimal 1
|
||||
* @group Camera trigger
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 0.5f);
|
||||
|
@ -79,14 +83,17 @@ PARAM_DEFINE_FLOAT(TRIG_ACT_TIME, 0.5f);
|
|||
/**
|
||||
* Camera trigger mode
|
||||
*
|
||||
* 0 disables the trigger, 1 sets it to enabled on command, 2 always on, 3 distance based, 4 distance based enabled on command
|
||||
* 0 disables the trigger, 1 sets it to enabled on command, 2 time based and always on,
|
||||
* 3 distance based and always on, 4 distance based and started / stopped via mission or command.
|
||||
*
|
||||
* @value 0 Disable
|
||||
* @value 1 CMD
|
||||
* @value 2 Always
|
||||
* @value 3 Distance
|
||||
* @value 1 On invididual commands
|
||||
* @value 2 Time based, always on
|
||||
* @value 3 Distance based, always on
|
||||
* @value 4 Distance, mission controlled
|
||||
* @min 0
|
||||
* @max 4
|
||||
* @reboot_required true
|
||||
* @group Camera trigger
|
||||
*/
|
||||
PARAM_DEFINE_INT32(TRIG_MODE, 0);
|
||||
|
@ -98,6 +105,8 @@ PARAM_DEFINE_INT32(TRIG_MODE, 0);
|
|||
*
|
||||
* @min 1
|
||||
* @max 123456
|
||||
* @decimal 0
|
||||
* @reboot_required true
|
||||
* @group Camera trigger
|
||||
*/
|
||||
PARAM_DEFINE_INT32(TRIG_PINS, 12);
|
||||
|
@ -109,6 +118,8 @@ PARAM_DEFINE_INT32(TRIG_PINS, 12);
|
|||
*
|
||||
* @unit m
|
||||
* @min 0
|
||||
* @increment 1
|
||||
* @decimal 1
|
||||
* @group Camera trigger
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(TRIG_DISTANCE, 25.0f);
|
||||
|
|
Loading…
Reference in New Issue