GCS_MAVLink: add support for request_message
This commit is contained in:
parent
9c8a7efbc6
commit
0ef26a6950
@ -374,6 +374,7 @@ protected:
|
||||
MAV_RESULT handle_command_set_message_interval(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_get_message_interval(const mavlink_command_long_t &packet);
|
||||
bool get_ap_message_interval(ap_message id, uint16_t &interval_ms) const;
|
||||
MAV_RESULT handle_command_request_message(const mavlink_command_long_t &packet);
|
||||
|
||||
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
|
||||
virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet);
|
||||
|
@ -2316,6 +2316,17 @@ MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_comman
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_long_t &packet)
|
||||
{
|
||||
const uint32_t mavlink_id = (uint32_t)packet.param1;
|
||||
const ap_message id = mavlink_id_to_ap_message_id(mavlink_id);
|
||||
if (id == MSG_LAST) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
send_message(id);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::get_ap_message_interval(ap_message id, uint16_t &interval_ms) const
|
||||
{
|
||||
// check if it's a specially-handled message:
|
||||
@ -3657,6 +3668,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
||||
result = handle_command_get_message_interval(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_REQUEST_MESSAGE:
|
||||
result = handle_command_request_message(packet);
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_SERVO:
|
||||
case MAV_CMD_DO_REPEAT_SERVO:
|
||||
case MAV_CMD_DO_SET_RELAY:
|
||||
|
Loading…
Reference in New Issue
Block a user