Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions libraries/AP_Mount/AP_Mount_MAVLink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,6 +139,9 @@ void AP_Mount_MAVLink::handle_gimbal_device_information(const mavlink_message_t
strncpy(vendor_name, info.vendor_name, ARRAY_SIZE(vendor_name));
strncpy(model_name, info.model_name, ARRAY_SIZE(model_name));

// prefer the 32-bit extension, fall back to the 16-bit field:
device_capapability_flags = (info.cap_flags2 != 0) ? info.cap_flags2 : info.cap_flags;

// display gimbal info to user
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mount: %s %s fw:%u.%u.%u.%u",
info.vendor_name,
Expand Down
16 changes: 14 additions & 2 deletions libraries/AP_Mount/AP_Mount_MAVLink.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,16 @@ class AP_Mount_MAVLink : public AP_Mount_Backend
(1U<<unsigned(MountTargetType::RETRACTED))
);

// temporary hack until we get GIMBAL_DEVICE_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL
// remove in ArduPilot-4.9; was a temporary hack until we got
// GIMBAL_DEVICE_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL
if ((strncmp(vendor_name, "AVTA", 4) == 0) && (strncmp(model_name, "CM41", 4) != 0)){
supported_target |= (1U<<unsigned(MountTargetType::LOCATION));
}


if (has_capability(GIMBAL_DEVICE_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL)) {
supported_target |= (1U<<unsigned(MountTargetType::LOCATION));
}

return supported_target;
};

Expand All @@ -60,6 +65,12 @@ class AP_Mount_MAVLink : public AP_Mount_Backend

private:

// returns true if the camera is reporting that it has the
// capability indicated by flag
bool has_capability(GIMBAL_DEVICE_CAP_FLAGS flag) const {
Comment thread
rmackay9 marked this conversation as resolved.
return device_capapability_flags & flag;
}

// search for gimbal in GCS_MAVLink routing table
void find_gimbal();

Expand Down Expand Up @@ -93,5 +104,6 @@ class AP_Mount_MAVLink : public AP_Mount_Backend
uint32_t _last_attitude_status_ms; // system time last attitude status was received (used for health reporting)
char vendor_name[MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_VENDOR_NAME_LEN]; // vendor name
char model_name[MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_MODEL_NAME_LEN]; // model name
uint32_t device_capapability_flags; // from GIMBAL_DEVICE_INFORMATION
};
#endif // HAL_MOUNT_MAVLINK_ENABLED
2 changes: 1 addition & 1 deletion modules/mavlink
Loading