mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: support camera-thermal-range
This commit is contained in:
parent
d18a2b22f9
commit
2db7a9520a
@ -1060,7 +1060,10 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
|
||||
{ MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS},
|
||||
{ MAVLINK_MSG_ID_CAMERA_FOV_STATUS, MSG_CAMERA_FOV_STATUS},
|
||||
{ MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, MSG_CAMERA_CAPTURE_STATUS},
|
||||
#endif
|
||||
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||
{ MAVLINK_MSG_ID_CAMERA_THERMAL_RANGE, MSG_CAMERA_THERMAL_RANGE},
|
||||
#endif // AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||
#endif // AP_CAMERA_ENABLED
|
||||
#if HAL_MOUNT_ENABLED
|
||||
{ MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS},
|
||||
{ MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE},
|
||||
@ -6131,6 +6134,9 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
case MSG_CAMERA_FOV_STATUS:
|
||||
#endif
|
||||
case MSG_CAMERA_CAPTURE_STATUS:
|
||||
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
|
||||
case MSG_CAMERA_THERMAL_RANGE:
|
||||
#endif
|
||||
{
|
||||
AP_Camera *camera = AP::camera();
|
||||
if (camera == nullptr) {
|
||||
|
@ -57,6 +57,7 @@ enum ap_message : uint8_t {
|
||||
MSG_CAMERA_SETTINGS,
|
||||
MSG_CAMERA_FOV_STATUS,
|
||||
MSG_CAMERA_CAPTURE_STATUS,
|
||||
MSG_CAMERA_THERMAL_RANGE,
|
||||
MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,
|
||||
MSG_GIMBAL_MANAGER_INFORMATION,
|
||||
MSG_GIMBAL_MANAGER_STATUS,
|
||||
|
Loading…
Reference in New Issue
Block a user