AP_Mount: fix sending camera information and settings for each backend

This commit is contained in:
Asif Khan 2023-08-02 00:04:14 +05:30 committed by Randy Mackay
parent 09e949173d
commit ea9f4a79f5
2 changed files with 12 additions and 14 deletions

View File

@ -805,25 +805,23 @@ bool AP_Mount::set_lens(uint8_t instance, uint8_t lens)
}
// send camera information message to GCS
void AP_Mount::send_camera_information(mavlink_channel_t chan) const
void AP_Mount::send_camera_information(uint8_t instance, mavlink_channel_t chan) const
{
// call send_camera_information for each instance
for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
if (_backends[instance] != nullptr) {
_backends[instance]->send_camera_information(chan);
}
auto *backend = get_instance(instance);
if (backend == nullptr) {
return;
}
_backends[instance]->send_camera_information(chan);
}
// send camera settings message to GCS
void AP_Mount::send_camera_settings(mavlink_channel_t chan) const
void AP_Mount::send_camera_settings(uint8_t instance, mavlink_channel_t chan) const
{
// call send_camera_settings for each instance
for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
if (_backends[instance] != nullptr) {
_backends[instance]->send_camera_settings(chan);
}
auto *backend = get_instance(instance);
if (backend == nullptr) {
return;
}
_backends[instance]->send_camera_settings(chan);
}
AP_Mount_Backend *AP_Mount::get_primary() const

View File

@ -242,10 +242,10 @@ public:
bool set_lens(uint8_t instance, uint8_t lens);
// send camera information message to GCS
void send_camera_information(mavlink_channel_t chan) const;
void send_camera_information(uint8_t instance, mavlink_channel_t chan) const;
// send camera settings message to GCS
void send_camera_settings(mavlink_channel_t chan) const;
void send_camera_settings(uint8_t instance, mavlink_channel_t chan) const;
// parameter var table
static const struct AP_Param::GroupInfo var_info[];