mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 22:48:28 -04:00
AP_Camera: Use SI units conventions in parameter units
Follow the rules from: http://physics.nist.gov/cuu/Units/units.html http://physics.nist.gov/cuu/Units/outside.html and http://physics.nist.gov/cuu/Units/checklist.html one further constrain is that only printable (7bit) ASCII characters are allowed
This commit is contained in:
parent
a85b7af32d
commit
41a9402175
@ -26,7 +26,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
||||
// @Param: DURATION
|
||||
// @DisplayName: Duration that shutter is held open
|
||||
// @Description: How long the shutter will be held open in 10ths of a second (i.e. enter 10 for 1second, 50 for 5seconds)
|
||||
// @Units: deciseconds
|
||||
// @Units: ds
|
||||
// @Range: 0 50
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("DURATION", 1, AP_Camera, _trigger_duration, AP_CAMERA_TRIGGER_DEFAULT_DURATION),
|
||||
@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
||||
// @Param: SERVO_ON
|
||||
// @DisplayName: Servo ON PWM value
|
||||
// @Description: PWM value to move servo to when shutter is activated
|
||||
// @Units: pwm
|
||||
// @Units: PWM
|
||||
// @Range: 1000 2000
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SERVO_ON", 2, AP_Camera, _servo_on_pwm, AP_CAMERA_SERVO_ON_PWM),
|
||||
@ -42,7 +42,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
||||
// @Param: SERVO_OFF
|
||||
// @DisplayName: Servo OFF PWM value
|
||||
// @Description: PWM value to move servo to when shutter is deactivated
|
||||
// @Units: pwm
|
||||
// @Units: PWM
|
||||
// @Range: 1000 2000
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SERVO_OFF", 3, AP_Camera, _servo_off_pwm, AP_CAMERA_SERVO_OFF_PWM),
|
||||
@ -51,7 +51,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
||||
// @DisplayName: Camera trigger distance
|
||||
// @Description: Distance in meters between camera triggers. If this value is non-zero then the camera will trigger whenever the GPS 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.
|
||||
// @User: Standard
|
||||
// @Units: meters
|
||||
// @Units: m
|
||||
// @Range: 0 1000
|
||||
AP_GROUPINFO("TRIGG_DIST", 4, AP_Camera, _trigg_dist, 0),
|
||||
|
||||
@ -66,7 +66,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
||||
// @DisplayName: Minimum time between photos
|
||||
// @Description: Postpone shooting if previous picture was taken less than preset time(ms) ago.
|
||||
// @User: Standard
|
||||
// @Units: milliseconds
|
||||
// @Units: ms
|
||||
// @Range: 0 10000
|
||||
AP_GROUPINFO("MIN_INTERVAL", 6, AP_Camera, _min_interval, 0),
|
||||
|
||||
@ -74,7 +74,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
||||
// @DisplayName: Maximum photo roll angle.
|
||||
// @Description: Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).
|
||||
// @User: Standard
|
||||
// @Units: Degrees
|
||||
// @Units: deg
|
||||
// @Range: 0 180
|
||||
AP_GROUPINFO("MAX_ROLL", 7, AP_Camera, _max_roll, 0),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user