mirror of https://github.com/ArduPilot/ardupilot
Moved mavlink_check_target() to the libraries/.
This allows it to be reused by the other libraries and by other projects ArduPlane, ArduCopter, ArduRover ... etc. It also reduces code duplication
This commit is contained in:
parent
c9c73dbdf0
commit
a3152b2410
|
@ -8,23 +8,6 @@
|
|||
byte mavdelay = 0;
|
||||
|
||||
|
||||
static uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
|
||||
{
|
||||
//Serial.print("target = "); Serial.print(sysid, DEC); Serial.print("\tcomp = "); Serial.println(compid, DEC);
|
||||
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
|
||||
//}else if(compid != mavlink_system.compid){
|
||||
// gcs.send_text_P(SEVERITY_LOW,PSTR("component id mismatch"));
|
||||
// return 1; // XXX currently not receiving correct compid from gcs
|
||||
|
||||
}else{
|
||||
return 0; // no error
|
||||
}
|
||||
}
|
||||
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
|
||||
|
||||
/*
|
||||
|
|
|
@ -8,16 +8,6 @@ static bool in_mavlink_delay;
|
|||
static mavlink_statustext_t pending_status;
|
||||
|
||||
|
||||
static 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
|
||||
}
|
||||
|
||||
|
||||
// check if a message will fit in the payload space available
|
||||
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
|
||||
|
||||
|
|
|
@ -12,3 +12,12 @@ BetterStream *mavlink_comm_1_port;
|
|||
mavlink_system_t mavlink_system = {7,1,0,0};
|
||||
|
||||
#include "include/mavlink_helpers.h"
|
||||
|
||||
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
|
||||
}
|
||||
|
|
|
@ -111,4 +111,6 @@ static inline int comm_get_txspace(mavlink_channel_t chan)
|
|||
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
#include "include/ardupilotmega/mavlink.h"
|
||||
|
||||
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid);
|
||||
|
||||
#endif // GCS_MAVLink_h
|
||||
|
|
Loading…
Reference in New Issue