GCS_MAVLink: enable sending of RELAY_STATUS message
This commit is contained in:
parent
1e18ca595f
commit
13c83ee9f8
@ -768,6 +768,7 @@ private:
|
|||||||
virtual void handleMessage(const mavlink_message_t &msg) = 0;
|
virtual void handleMessage(const mavlink_message_t &msg) = 0;
|
||||||
|
|
||||||
MAV_RESULT handle_servorelay_message(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_servorelay_message(const mavlink_command_long_t &packet);
|
||||||
|
bool send_relay_status() const;
|
||||||
|
|
||||||
static bool command_long_stores_location(const MAV_CMD command);
|
static bool command_long_stores_location(const MAV_CMD command);
|
||||||
|
|
||||||
|
@ -1035,6 +1035,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
|
|||||||
#endif
|
#endif
|
||||||
#if HAL_ADSB_ENABLED
|
#if HAL_ADSB_ENABLED
|
||||||
{ MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, MSG_UAVIONIX_ADSB_OUT_STATUS},
|
{ MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, MSG_UAVIONIX_ADSB_OUT_STATUS},
|
||||||
|
#endif
|
||||||
|
#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
|
||||||
|
{ MAVLINK_MSG_ID_RELAY_STATUS, MSG_RELAY_STATUS},
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -5534,6 +5537,19 @@ void GCS_MAVLINK::send_uavionix_adsb_out_status() const
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
|
||||||
|
bool GCS_MAVLINK::send_relay_status() const
|
||||||
|
{
|
||||||
|
AP_Relay *relay = AP::relay();
|
||||||
|
if (relay == nullptr) {
|
||||||
|
// must only return false if out of space:
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return relay->send_relay_status(*this);
|
||||||
|
}
|
||||||
|
#endif // AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
|
||||||
|
|
||||||
void GCS_MAVLINK::send_autopilot_state_for_gimbal_device() const
|
void GCS_MAVLINK::send_autopilot_state_for_gimbal_device() const
|
||||||
{
|
{
|
||||||
// get attitude
|
// get attitude
|
||||||
@ -5994,6 +6010,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_RELAY_STATUS:
|
||||||
|
#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
|
||||||
|
ret = send_relay_status();
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
default:
|
default:
|
||||||
// try_send_message must always at some stage return true for
|
// try_send_message must always at some stage return true for
|
||||||
// a message, or we will attempt to infinitely retry the
|
// a message, or we will attempt to infinitely retry the
|
||||||
|
@ -1,6 +1,7 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL_Boards.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
#include <AP_Relay/AP_Relay_config.h>
|
||||||
|
|
||||||
#ifndef HAL_GCS_ENABLED
|
#ifndef HAL_GCS_ENABLED
|
||||||
#define HAL_GCS_ENABLED 1
|
#define HAL_GCS_ENABLED 1
|
||||||
@ -40,3 +41,6 @@
|
|||||||
#define HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED ((AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED) && BOARD_FLASH_SIZE > 1024)
|
#define HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED ((AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED) && BOARD_FLASH_SIZE > 1024)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_MAVLINK_MSG_RELAY_STATUS_ENABLED
|
||||||
|
#define AP_MAVLINK_MSG_RELAY_STATUS_ENABLED HAL_GCS_ENABLED && AP_RELAY_ENABLED
|
||||||
|
#endif
|
||||||
|
@ -87,5 +87,6 @@ enum ap_message : uint8_t {
|
|||||||
MSG_ATTITUDE_TARGET,
|
MSG_ATTITUDE_TARGET,
|
||||||
MSG_HYGROMETER,
|
MSG_HYGROMETER,
|
||||||
MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE,
|
MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE,
|
||||||
|
MSG_RELAY_STATUS,
|
||||||
MSG_LAST // MSG_LAST must be the last entry in this enum
|
MSG_LAST // MSG_LAST must be the last entry in this enum
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user