AP_Mount: Xacti sends gimbal_device_id in camera_information
This commit is contained in:
parent
d242a968f3
commit
25e8bd1f42
@ -231,7 +231,8 @@ void AP_Mount_Xacti::send_camera_information(mavlink_channel_t chan) const
|
||||
0, // lens_id uint8_t
|
||||
flags, // flags uint32_t (CAMERA_CAP_FLAGS)
|
||||
0, // cam_definition_version uint16_t
|
||||
cam_definition_uri); // cam_definition_uri char[140]
|
||||
cam_definition_uri, // cam_definition_uri char[140]
|
||||
_instance + 1); // gimbal_device_id uint8_t
|
||||
}
|
||||
|
||||
// send camera settings message to GCS
|
||||
|
Loading…
Reference in New Issue
Block a user