Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Camera/AP_Camera_Params.cpp
Views: 1798
#include "AP_Camera_Params.h"12// table of user settable parameters3const AP_Param::GroupInfo AP_Camera_Params::var_info[] = {45// 0 should not be used67// @Param: _TYPE8// @DisplayName: Camera shutter (trigger) type9// @Description: how to trigger the camera to take a picture10// @Values: 0:None, 1:Servo, 2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi/Topotek/Viewpro/Xacti), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting, 8:RunCam11// @User: Standard12AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Camera_Params, type, 0, AP_PARAM_FLAG_ENABLE),1314// @Param: _DURATION15// @DisplayName: Camera shutter duration held open16// @Description: Duration in seconds that the camera shutter is held open17// @Units: s18// @Range: 0 519// @User: Standard20AP_GROUPINFO("_DURATION", 2, AP_Camera_Params, trigger_duration, 0.1),2122// @Param: _SERVO_ON23// @DisplayName: Camera servo ON PWM value24// @Description: PWM value in microseconds to move servo to when shutter is activated25// @Units: PWM26// @Range: 1000 200027// @User: Standard28AP_GROUPINFO("_SERVO_ON", 3, AP_Camera_Params, servo_on_pwm, 1300),2930// @Param: _SERVO_OFF31// @DisplayName: Camera servo OFF PWM value32// @Description: PWM value in microseconds to move servo to when shutter is deactivated33// @Units: PWM34// @Range: 1000 200035// @User: Standard36AP_GROUPINFO("_SERVO_OFF", 4, AP_Camera_Params, servo_off_pwm, 1100),3738// @Param: _TRIGG_DIST39// @DisplayName: Camera trigger distance40// @Description: Distance in meters between camera triggers. If this value is non-zero then the camera will trigger whenever the position changes by this number of meters regardless of what mode the APM is in. Note that this parameter can also be set in an auto mission using the DO_SET_CAM_TRIGG_DIST command, allowing you to enable/disable the triggering of the camera during the flight.41// @User: Standard42// @Units: m43// @Range: 0 100044AP_GROUPINFO("_TRIGG_DIST", 5, AP_Camera_Params, trigg_dist, 0),4546// @Param: _RELAY_ON47// @DisplayName: Camera relay ON value48// @Description: This sets whether the relay goes high or low when it triggers. Note that you should also set RELAY_DEFAULT appropriately for your camera49// @Values: 0:Low,1:High50// @User: Standard51AP_GROUPINFO("_RELAY_ON", 6, AP_Camera_Params, relay_on, 1),5253// @Param: _INTRVAL_MIN54// @DisplayName: Camera minimum time interval between photos55// @Description: Postpone shooting if previous picture was taken less than this many seconds ago56// @Units: s57// @Range: 0 1058// @User: Standard59AP_GROUPINFO("_INTRVAL_MIN", 7, AP_Camera_Params, interval_min, 0),6061// @Param: _FEEDBAK_PIN62// @DisplayName: Camera feedback pin63// @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. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. See also the CAMx_FEEDBCK_POL option.64// @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX665// @User: Standard66// @RebootRequired: True67AP_GROUPINFO("_FEEDBAK_PIN", 8, AP_Camera_Params, feedback_pin, -1),6869// @Param: _FEEDBAK_POL70// @DisplayName: Camera feedback pin polarity71// @Description: Polarity for feedback pin. If this is 1 then the feedback pin should go high on trigger. If set to 0 then it should go low72// @Values: 0:TriggerLow,1:TriggerHigh73// @User: Standard74AP_GROUPINFO("_FEEDBAK_POL", 9, AP_Camera_Params, feedback_polarity, 1),7576// @Param: _OPTIONS77// @DisplayName: Camera options78// @Description: Camera options bitmask79// @Bitmask: 0:Recording Starts at arming and stops at disarming80// @User: Standard81AP_GROUPINFO("_OPTIONS", 10, AP_Camera_Params, options, 0),8283// @Param: _MNT_INST84// @DisplayName: Camera Mount instance85// @Description: Mount instance camera is associated with. 0 means camera and mount have identical instance numbers e.g. camera1 and mount186// @User: Standard87AP_GROUPINFO("_MNT_INST", 11, AP_Camera_Params, mount_instance, 0),8889// @Param: _HFOV90// @DisplayName: Camera horizontal field of view91// @Description: Camera horizontal field of view. 0 if unknown92// @Units: deg93// @Range: 0 36094// @User: Standard95AP_GROUPINFO("_HFOV", 12, AP_Camera_Params, hfov, 0),9697// @Param: _VFOV98// @DisplayName: Camera vertical field of view99// @Description: Camera vertical field of view. 0 if unknown100// @Units: deg101// @Range: 0 180102// @User: Standard103AP_GROUPINFO("_VFOV", 13, AP_Camera_Params, vfov, 0),104105AP_GROUPEND106107};108109AP_Camera_Params::AP_Camera_Params(void) {110AP_Param::setup_object_defaults(this, var_info);111}112113114