Skip to content

Commit a59c867

Browse files
committed
AP_Mount: use new GIMBAL_DEVICE_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL
we had a temporary hack in place for the AVT gimbals to use. Replace with the standardised bit
1 parent 2ab8345 commit a59c867

2 files changed

Lines changed: 17 additions & 2 deletions

File tree

libraries/AP_Mount/AP_Mount_MAVLink.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -139,6 +139,9 @@ void AP_Mount_MAVLink::handle_gimbal_device_information(const mavlink_message_t
139139
strncpy(vendor_name, info.vendor_name, ARRAY_SIZE(vendor_name));
140140
strncpy(model_name, info.model_name, ARRAY_SIZE(model_name));
141141

142+
// prefer the 32-bit extension, fall back to the 16-bit field:
143+
device_capapability_flags = (info.cap_flags2 != 0) ? info.cap_flags2 : info.cap_flags;
144+
142145
// display gimbal info to user
143146
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mount: %s %s fw:%u.%u.%u.%u",
144147
info.vendor_name,

libraries/AP_Mount/AP_Mount_MAVLink.h

Lines changed: 14 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -47,11 +47,16 @@ class AP_Mount_MAVLink : public AP_Mount_Backend
4747
(1U<<unsigned(MountTargetType::RETRACTED))
4848
);
4949

50-
// temporary hack until we get GIMBAL_DEVICE_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL
50+
// remove in ArduPilot-4.9; was a temporary hack until we got
51+
// GIMBAL_DEVICE_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL
5152
if ((strncmp(vendor_name, "AVTA", 4) == 0) && (strncmp(model_name, "CM41", 4) != 0)){
5253
supported_target |= (1U<<unsigned(MountTargetType::LOCATION));
5354
}
54-
55+
56+
if (has_capability(GIMBAL_DEVICE_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL)) {
57+
supported_target |= (1U<<unsigned(MountTargetType::LOCATION));
58+
}
59+
5560
return supported_target;
5661
};
5762

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

6166
private:
6267

68+
// returns true if the camera is reporting that it has the
69+
// capability indicated by flag
70+
bool has_capability(GIMBAL_DEVICE_CAP_FLAGS flag) const {
71+
return device_capapability_flags & flag;
72+
}
73+
6374
// search for gimbal in GCS_MAVLink routing table
6475
void find_gimbal();
6576

@@ -93,5 +104,6 @@ class AP_Mount_MAVLink : public AP_Mount_Backend
93104
uint32_t _last_attitude_status_ms; // system time last attitude status was received (used for health reporting)
94105
char vendor_name[MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_VENDOR_NAME_LEN]; // vendor name
95106
char model_name[MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_MODEL_NAME_LEN]; // model name
107+
uint32_t device_capapability_flags; // from GIMBAL_DEVICE_INFORMATION
96108
};
97109
#endif // HAL_MOUNT_MAVLINK_ENABLED

0 commit comments

Comments
 (0)