Tools: custom build server support for SEND_FOV_STATUS
This commit is contained in:
parent
8a791d6082
commit
6528394797
@ -123,6 +123,7 @@ BUILD_OPTIONS = [
|
||||
Feature('Camera', 'Camera_Relay', 'AP_CAMERA_RELAY_ENABLED', 'Enable Camera Trigger via Relay support', 0, 'Camera,RELAY'),
|
||||
Feature('Camera', 'Camera_Servo', 'AP_CAMERA_SERVO_ENABLED', 'Enable Camera Trigger via Servo support', 0, 'Camera'),
|
||||
Feature('Camera', 'Camera_Solo', 'AP_CAMERA_SOLOGIMBAL_ENABLED', 'Enable Solo Gimbal support', 0, 'Camera'),
|
||||
Feature('Camera', 'Camera_FOV_Status', 'AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'Enable Camera FOV Status send to GCS', 0, 'Camera,MOUNT'), # noqa: E501
|
||||
|
||||
Feature('Camera', 'RUNCAM', 'HAL_RUNCAM_ENABLED', 'Enable RunCam Control', 0, None),
|
||||
|
||||
|
@ -122,6 +122,7 @@ class ExtractFeatures(object):
|
||||
|
||||
('AP_CAMERA_ENABLED', 'AP_Camera::var_info',),
|
||||
('AP_CAMERA_{type}_ENABLED', 'AP_Camera_(?P<type>.*)::trigger_pic',),
|
||||
('AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'AP_Camera::send_camera_fov_status'),
|
||||
('HAL_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',),
|
||||
|
||||
('HAL_PROXIMITY_ENABLED', 'AP_Proximity::AP_Proximity',),
|
||||
|
Loading…
Reference in New Issue
Block a user