mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
GCS_MAVLink: handle message interval commands as both long and int
This commit is contained in:
parent
c1110d4b43
commit
423a88f9cd
@ -580,10 +580,10 @@ protected:
|
|||||||
void deadlock_sem(void);
|
void deadlock_sem(void);
|
||||||
|
|
||||||
// reset a message interval via mavlink:
|
// reset a message interval via mavlink:
|
||||||
MAV_RESULT handle_command_set_message_interval(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_set_message_interval(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_command_get_message_interval(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_get_message_interval(const mavlink_command_int_t &packet);
|
||||||
bool get_ap_message_interval(ap_message id, uint16_t &interval_ms) const;
|
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_command_request_message(const mavlink_command_int_t &packet);
|
||||||
|
|
||||||
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
|
||||||
|
|
||||||
|
@ -2847,7 +2847,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_lon
|
|||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
return set_message_interval((uint32_t)packet.param1, (int32_t)packet.param2);
|
return set_message_interval((uint32_t)packet.param1, (int32_t)packet.param2);
|
||||||
}
|
}
|
||||||
@ -2917,7 +2917,7 @@ uint8_t GCS::get_channel_from_port_number(uint8_t port_num)
|
|||||||
return UINT8_MAX;
|
return UINT8_MAX;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
const uint32_t mavlink_id = (uint32_t)packet.param1;
|
const uint32_t mavlink_id = (uint32_t)packet.param1;
|
||||||
const ap_message id = mavlink_id_to_ap_message_id(mavlink_id);
|
const ap_message id = mavlink_id_to_ap_message_id(mavlink_id);
|
||||||
@ -2949,7 +2949,7 @@ bool GCS_MAVLINK::get_ap_message_interval(ap_message id, uint16_t &interval_ms)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_get_message_interval(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_get_message_interval(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
if (txspace() < PAYLOAD_SIZE(chan, MESSAGE_INTERVAL) + PAYLOAD_SIZE(chan, COMMAND_ACK)) {
|
if (txspace() < PAYLOAD_SIZE(chan, MESSAGE_INTERVAL) + PAYLOAD_SIZE(chan, COMMAND_ACK)) {
|
||||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
return MAV_RESULT_TEMPORARILY_REJECTED;
|
||||||
@ -4840,18 +4840,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
|||||||
result = handle_command_do_aux_function(packet);
|
result = handle_command_do_aux_function(packet);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_SET_MESSAGE_INTERVAL:
|
|
||||||
result = handle_command_set_message_interval(packet);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAV_CMD_GET_MESSAGE_INTERVAL:
|
|
||||||
result = handle_command_get_message_interval(packet);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MAV_CMD_REQUEST_MESSAGE:
|
|
||||||
result = handle_command_request_message(packet);
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
result = try_command_long_as_command_int(packet, msg);
|
result = try_command_long_as_command_int(packet, msg);
|
||||||
break;
|
break;
|
||||||
@ -5167,6 +5155,18 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
|
|||||||
case MAV_CMD_STORAGE_FORMAT:
|
case MAV_CMD_STORAGE_FORMAT:
|
||||||
return handle_command_storage_format(packet, msg);
|
return handle_command_storage_format(packet, msg);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// support for dealing with streamrate for a specific message and
|
||||||
|
// requesting a message instance:
|
||||||
|
case MAV_CMD_SET_MESSAGE_INTERVAL:
|
||||||
|
return handle_command_set_message_interval(packet);
|
||||||
|
|
||||||
|
case MAV_CMD_GET_MESSAGE_INTERVAL:
|
||||||
|
return handle_command_get_message_interval(packet);
|
||||||
|
|
||||||
|
case MAV_CMD_REQUEST_MESSAGE:
|
||||||
|
return handle_command_request_message(packet);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return MAV_RESULT_UNSUPPORTED;
|
return MAV_RESULT_UNSUPPORTED;
|
||||||
|
Loading…
Reference in New Issue
Block a user