mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: clearer parameter docs for trigger pin
This commit is contained in:
parent
bb5db870cb
commit
e83a3d8185
|
@ -82,8 +82,8 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
|||
|
||||
// @Param: FEEDBACK_PIN
|
||||
// @DisplayName: Camera feedback pin
|
||||
// @Description: pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. See also the CAM_FEEDBACK_POL option
|
||||
// @Values: -1:Disabled, 0-8:APM FeedbackPin,50-55:PixHawk FeedbackPin
|
||||
// @Description: pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. See also the CAM_FEEDBACK_POL option. If using AUX4 pin on a Pixhawk then a fast capture method is used that allows for the trigger time to be as short as one microsecond.
|
||||
// @Values: -1:Disabled,50:PX4 AUX1,51:PX4 AUX2,52:PX4 AUX3,53:PX4 AUX4(fast capture),54:PX4 AUX5,55:PX4 AUX6
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("FEEDBACK_PIN", 8, AP_Camera, _feedback_pin, AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN),
|
||||
|
||||
|
|
Loading…
Reference in New Issue