AP_Camera: backend sends gimbal_device_id in camera_information

This commit is contained in:
davidsastresas 2023-07-19 16:02:50 +02:00 committed by Randy Mackay
parent 6a9b457be3
commit 9bca2740b2
2 changed files with 22 additions and 1 deletions

View File

@ -3,6 +3,7 @@
#if AP_CAMERA_ENABLED
#include <GCS_MAVLink/GCS.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Mount/AP_Mount.h>
extern const AP_HAL::HAL& hal;
@ -103,6 +104,22 @@ uint8_t AP_Camera_Backend::get_mount_instance() const
return _params.mount_instance.get() - 1;
}
// get mavlink gimbal device id which is normally mount_instance+1
uint8_t AP_Camera_Backend::get_gimbal_device_id() const
{
#if HAL_MOUNT_ENABLED
const uint8_t mount_instance = get_mount_instance();
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
if (mount->get_mount_type(mount_instance) != AP_Mount::Type::None) {
return (mount_instance + 1);
}
}
#endif
return 0;
}
// take a picture. returns true on success
bool AP_Camera_Backend::take_picture()
{
@ -206,7 +223,8 @@ void AP_Camera_Backend::send_camera_information(mavlink_channel_t chan) const
0, // lens_id, uint8_t
cap_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]
get_gimbal_device_id());// gimbal_device_id uint8_t
}
// send camera settings message to GCS

View File

@ -147,6 +147,9 @@ protected:
// get corresponding mount instance for the camera
uint8_t get_mount_instance() const;
// get mavlink gimbal device id which is normally mount_instance+1
uint8_t get_gimbal_device_id() const;
// internal members
uint8_t _instance; // this instance's number
bool timer_installed; // true if feedback pin change detected using timer