GCS_MAVLink: removed use of mavlink_check_target()
not needed now we do routing properly, as messages will only be processed if they are for us
This commit is contained in:
parent
aa88ba4158
commit
f1edd1bafb
@ -232,11 +232,6 @@ void GCS_MAVLINK::handle_mission_request_list(AP_Mission &mission, mavlink_messa
|
||||
mavlink_mission_request_list_t packet;
|
||||
mavlink_msg_mission_request_list_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// reply with number of commands in the mission. The GCS will then request each command separately
|
||||
mavlink_msg_mission_count_send(chan,msg->sysid, msg->compid, mission.num_commands());
|
||||
|
||||
@ -256,11 +251,6 @@ void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t
|
||||
mavlink_mission_request_t packet;
|
||||
mavlink_msg_mission_request_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// retrieve mission from eeprom
|
||||
if (!mission.read_cmd_from_storage(packet.seq, cmd)) {
|
||||
goto mission_item_send_failed;
|
||||
@ -314,11 +304,6 @@ void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, mavlink_messag
|
||||
mavlink_mission_set_current_t packet;
|
||||
mavlink_msg_mission_set_current_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// set current command
|
||||
if (mission.set_current_cmd(packet.seq)) {
|
||||
mavlink_msg_mission_current_send(chan, mission.get_current_nav_cmd().index);
|
||||
@ -334,11 +319,6 @@ void GCS_MAVLINK::handle_mission_count(AP_Mission &mission, mavlink_message_t *m
|
||||
mavlink_mission_count_t packet;
|
||||
mavlink_msg_mission_count_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// start waypoint receiving
|
||||
if (packet.count > mission.num_commands_max()) {
|
||||
// send NAK
|
||||
@ -366,11 +346,6 @@ void GCS_MAVLINK::handle_mission_clear_all(AP_Mission &mission, mavlink_message_
|
||||
mavlink_mission_clear_all_t packet;
|
||||
mavlink_msg_mission_clear_all_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// clear all waypoints
|
||||
if (mission.clear()) {
|
||||
// send ack
|
||||
@ -390,11 +365,6 @@ void GCS_MAVLINK::handle_mission_write_partial_list(AP_Mission &mission, mavlink
|
||||
mavlink_mission_write_partial_list_t packet;
|
||||
mavlink_msg_mission_write_partial_list_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// start waypoint receiving
|
||||
if ((unsigned)packet.start_index > mission.num_commands() ||
|
||||
(unsigned)packet.end_index > mission.num_commands() ||
|
||||
@ -444,10 +414,6 @@ void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg, bool save)
|
||||
mavlink_request_data_stream_t packet;
|
||||
mavlink_msg_request_data_stream_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component))
|
||||
return;
|
||||
|
||||
int16_t freq = 0; // packet frequency
|
||||
|
||||
if (packet.start_stop == 0)
|
||||
@ -509,11 +475,6 @@ void GCS_MAVLINK::handle_param_request_list(mavlink_message_t *msg)
|
||||
mavlink_param_request_list_t packet;
|
||||
mavlink_msg_param_request_list_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_APM1 && CONFIG_HAL_BOARD != HAL_BOARD_APM2
|
||||
// send system ID if we can
|
||||
char sysid[40];
|
||||
@ -533,10 +494,6 @@ void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg)
|
||||
mavlink_param_request_read_t packet;
|
||||
mavlink_msg_param_request_read_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
enum ap_var_type p_type;
|
||||
AP_Param *vp;
|
||||
char param_name[AP_MAX_NAME_SIZE+1];
|
||||
@ -576,11 +533,6 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class *Data
|
||||
mavlink_param_set_t packet;
|
||||
mavlink_msg_param_set_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// set parameter
|
||||
char key[AP_MAX_NAME_SIZE+1];
|
||||
strncpy(key, (char *)packet.param_id, AP_MAX_NAME_SIZE);
|
||||
@ -719,11 +671,6 @@ void GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &missio
|
||||
|
||||
mavlink_msg_mission_item_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system,packet.target_component)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// convert mavlink packet to mission command
|
||||
if (!AP_Mission::mavlink_to_mission_cmd(packet, cmd)) {
|
||||
result = MAV_MISSION_INVALID;
|
||||
@ -1182,11 +1129,6 @@ void GCS_MAVLINK::handle_set_mode(mavlink_message_t* msg, bool (*set_mode)(uint8
|
||||
mavlink_set_mode_t packet;
|
||||
mavlink_msg_set_mode_decode(msg, &packet);
|
||||
|
||||
// exit immediately if this command is not meant for this vehicle
|
||||
if (mavlink_check_target(packet.target_system, 0)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes
|
||||
if (packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
|
||||
if (set_mode(packet.custom_mode)) {
|
||||
|
@ -54,8 +54,7 @@ void GCS_MAVLINK::handle_log_request_list(mavlink_message_t *msg, DataFlash_Clas
|
||||
{
|
||||
mavlink_log_request_list_t packet;
|
||||
mavlink_msg_log_request_list_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component))
|
||||
return;
|
||||
|
||||
_log_listing = false;
|
||||
_log_sending = false;
|
||||
|
||||
@ -89,8 +88,6 @@ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Clas
|
||||
{
|
||||
mavlink_log_request_data_t packet;
|
||||
mavlink_msg_log_request_data_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component))
|
||||
return;
|
||||
|
||||
_log_listing = false;
|
||||
if (!_log_sending || _log_num_data != packet.id) {
|
||||
@ -132,8 +129,6 @@ void GCS_MAVLINK::handle_log_request_erase(mavlink_message_t *msg, DataFlash_Cla
|
||||
{
|
||||
mavlink_log_erase_t packet;
|
||||
mavlink_msg_log_erase_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component))
|
||||
return;
|
||||
|
||||
dataflash.EraseAll();
|
||||
}
|
||||
@ -145,8 +140,6 @@ void GCS_MAVLINK::handle_log_request_end(mavlink_message_t *msg, DataFlash_Class
|
||||
{
|
||||
mavlink_log_request_end_t packet;
|
||||
mavlink_msg_log_request_end_decode(msg, &packet);
|
||||
if (mavlink_check_target(packet.target_system, packet.target_component))
|
||||
return;
|
||||
_log_sending = false;
|
||||
}
|
||||
|
||||
|
@ -61,15 +61,6 @@ void GCS_MAVLINK::lock_channel(mavlink_channel_t _chan, bool lock)
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
|
||||
{
|
||||
if (sysid != mavlink_system.sysid)
|
||||
return 1;
|
||||
// Currently we are not checking for correct compid since APM is not passing mavlink info to any subsystem
|
||||
// If it is addressed to our system ID we assume it is for us
|
||||
return 0; // no error
|
||||
}
|
||||
|
||||
// return a MAVLink variable type given a AP_Param type
|
||||
uint8_t mav_var_type(enum ap_var_type t)
|
||||
{
|
||||
|
@ -128,8 +128,6 @@ bool comm_is_idle(mavlink_channel_t chan);
|
||||
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
#include "include/mavlink/v1.0/ardupilotmega/mavlink.h"
|
||||
|
||||
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid);
|
||||
|
||||
// return a MAVLink variable type given a AP_Param type
|
||||
uint8_t mav_var_type(enum ap_var_type t);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user