GCS_MAVLink: have GCS_MAVLINK::send_message(id, buffer) check size

This commit is contained in:
Peter Barker 2023-02-24 16:02:57 +11:00 committed by Peter Barker
parent e728f91798
commit adb364cd98
5 changed files with 17 additions and 20 deletions

View File

@ -93,10 +93,7 @@ void GCS::send_to_active_channels(uint32_t msgid, const char *pkt)
if (!c.is_active()) {
continue;
}
if (entry->max_msg_len + c.packet_overhead() > c.txspace()) {
// no room on this channel
continue;
}
// size checks done by this method:
c.send_message(pkt, entry);
}
}

View File

@ -244,15 +244,17 @@ public:
const mavlink_message_t &msg);
// send a mavlink_message_t out this GCS_MAVLINK connection.
// Caller is responsible for ensuring space.
void send_message(uint32_t msgid, const char *pkt) const {
void send_message(uint32_t msgid, const char *pkt) {
const mavlink_msg_entry_t *entry = mavlink_get_msg_entry(msgid);
if (entry == nullptr) {
return;
}
send_message(pkt, entry);
}
void send_message(const char *pkt, const mavlink_msg_entry_t *entry) const {
void send_message(const char *pkt, const mavlink_msg_entry_t *entry) {
if (!check_payload_size(entry->max_msg_len)) {
return;
}
_mav_finalize_message_chan_send(chan,
entry->msgid,
pkt,
@ -519,9 +521,9 @@ protected:
MAV_RESULT handle_command_do_aux_function(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_storage_format(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
void handle_mission_request_list(const mavlink_message_t &msg);
void handle_mission_request(const mavlink_message_t &msg) const;
void handle_mission_request_int(const mavlink_message_t &msg) const;
void handle_mission_clear_all(const mavlink_message_t &msg) const;
void handle_mission_request(const mavlink_message_t &msg);
void handle_mission_request_int(const mavlink_message_t &msg);
void handle_mission_clear_all(const mavlink_message_t &msg);
// Note that there exists a relatively new mavlink DO command,
// MAV_CMD_DO_SET_MISSION_CURRENT which provides an acknowledgement

View File

@ -589,7 +589,7 @@ void GCS_MAVLINK::handle_mission_request_list(const mavlink_message_t &msg)
/*
handle a MISSION_REQUEST mavlink packet
*/
void GCS_MAVLINK::handle_mission_request_int(const mavlink_message_t &msg) const
void GCS_MAVLINK::handle_mission_request_int(const mavlink_message_t &msg)
{
// decode
mavlink_mission_request_int_t packet;
@ -602,7 +602,7 @@ void GCS_MAVLINK::handle_mission_request_int(const mavlink_message_t &msg) const
prot->handle_mission_request_int(*this, packet, msg);
}
void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg) const
void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg)
{
// decode
mavlink_mission_request_t packet;
@ -674,7 +674,7 @@ void GCS_MAVLINK::handle_mission_count(const mavlink_message_t &msg)
/*
handle a MISSION_CLEAR_ALL mavlink packet
*/
void GCS_MAVLINK::handle_mission_clear_all(const mavlink_message_t &msg) const
void GCS_MAVLINK::handle_mission_clear_all(const mavlink_message_t &msg)
{
// decode
mavlink_mission_clear_all_t packet;

View File

@ -122,7 +122,7 @@ void MissionItemProtocol::handle_mission_request_list(
mission_type());
}
void MissionItemProtocol::handle_mission_request_int(const GCS_MAVLINK &_link,
void MissionItemProtocol::handle_mission_request_int(GCS_MAVLINK &_link,
const mavlink_mission_request_int_t &packet,
const mavlink_message_t &msg)
{
@ -152,11 +152,10 @@ void MissionItemProtocol::handle_mission_request_int(const GCS_MAVLINK &_link,
return;
}
CHECK_PAYLOAD_SIZE2_VOID(_link.get_chan(), MISSION_ITEM_INT);
_link.send_message(MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char*)&ret_packet);
}
void MissionItemProtocol::handle_mission_request(const GCS_MAVLINK &_link,
void MissionItemProtocol::handle_mission_request(GCS_MAVLINK &_link,
const mavlink_mission_request_t &packet,
const mavlink_message_t &msg
)
@ -191,13 +190,12 @@ void MissionItemProtocol::handle_mission_request(const GCS_MAVLINK &_link,
return;
}
CHECK_PAYLOAD_SIZE2_VOID(_link.get_chan(), MISSION_ITEM_INT);
if (!mission_request_warning_sent) {
mission_request_warning_sent = true;
gcs().send_text(MAV_SEVERITY_WARNING, "got MISSION_REQUEST; use MISSION_REQUEST_INT!");
}
// buffer space is checked by send_message
_link.send_message(MAVLINK_MSG_ID_MISSION_ITEM, (const char*)&ret_packet);
}

View File

@ -30,10 +30,10 @@ public:
void handle_mission_request_list(const class GCS_MAVLINK &link,
const mavlink_mission_request_list_t &packet,
const mavlink_message_t &msg);
void handle_mission_request_int(const GCS_MAVLINK &link,
void handle_mission_request_int(GCS_MAVLINK &link,
const mavlink_mission_request_int_t &packet,
const mavlink_message_t &msg);
void handle_mission_request(const GCS_MAVLINK &link,
void handle_mission_request(GCS_MAVLINK &link,
const mavlink_mission_request_t &packet,
const mavlink_message_t &msg);