mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: send `AVAILABLE_MODES_MONITOR` message
This commit is contained in:
parent
551a7b8a20
commit
55936895e3
|
@ -1139,6 +1139,7 @@ private:
|
|||
uint8_t next_index;
|
||||
} available_modes;
|
||||
bool send_available_modes();
|
||||
bool send_available_mode_monitor();
|
||||
|
||||
};
|
||||
|
||||
|
@ -1301,6 +1302,11 @@ public:
|
|||
MAV_RESULT lua_command_int_packet(const mavlink_command_int_t &packet);
|
||||
#endif
|
||||
|
||||
// Sequence number should be incremented when available modes changes
|
||||
// Sent in AVAILABLE_MODES_MONITOR msg
|
||||
uint8_t get_available_modes_sequence() const { return available_modes_sequence; }
|
||||
void available_modes_changed() { available_modes_sequence += 1; }
|
||||
|
||||
protected:
|
||||
|
||||
virtual GCS_MAVLINK *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
||||
|
@ -1378,6 +1384,10 @@ private:
|
|||
// GCS::update_send is called so we don't starve later links of
|
||||
// time in which they are permitted to send messages.
|
||||
uint8_t first_backend_to_send;
|
||||
|
||||
// Sequence number should be incremented when available modes changes
|
||||
// Sent in AVAILABLE_MODES_MONITOR msg
|
||||
uint8_t available_modes_sequence;
|
||||
};
|
||||
|
||||
GCS &gcs();
|
||||
|
|
|
@ -1153,6 +1153,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
|
|||
{ MAVLINK_MSG_ID_AIRSPEED, MSG_AIRSPEED},
|
||||
#endif
|
||||
{ MAVLINK_MSG_ID_AVAILABLE_MODES, MSG_AVAILABLE_MODES},
|
||||
{ MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR, MSG_AVAILABLE_MODES_MONITOR},
|
||||
};
|
||||
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(map); i++) {
|
||||
|
@ -3210,6 +3211,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_int
|
|||
available_modes.should_send = true;
|
||||
available_modes.next_index = 1;
|
||||
available_modes.requested_index = (uint8_t)packet.param2;
|
||||
|
||||
// After the first request sequnece is streamed in the AVAILABLE_MODES_MONITOR message
|
||||
// This allows the GCS to re-request modes if there is a change
|
||||
set_ap_message_interval(MSG_AVAILABLE_MODES_MONITOR, 5000);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -6137,6 +6142,18 @@ bool GCS_MAVLINK::send_available_modes()
|
|||
return true;
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::send_available_mode_monitor()
|
||||
{
|
||||
CHECK_PAYLOAD_SIZE(AVAILABLE_MODES_MONITOR);
|
||||
|
||||
mavlink_msg_available_modes_monitor_send(
|
||||
chan,
|
||||
gcs().get_available_modes_sequence()
|
||||
);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
{
|
||||
bool ret = true;
|
||||
|
@ -6571,6 +6588,10 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||
ret = send_available_modes();
|
||||
break;
|
||||
|
||||
case MSG_AVAILABLE_MODES_MONITOR:
|
||||
ret = send_available_mode_monitor();
|
||||
break;
|
||||
|
||||
default:
|
||||
// try_send_message must always at some stage return true for
|
||||
// a message, or we will attempt to infinitely retry the
|
||||
|
|
|
@ -104,5 +104,6 @@ enum ap_message : uint8_t {
|
|||
#endif
|
||||
MSG_AIRSPEED,
|
||||
MSG_AVAILABLE_MODES,
|
||||
MSG_AVAILABLE_MODES_MONITOR,
|
||||
MSG_LAST // MSG_LAST must be the last entry in this enum
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue