2010-11-25 02:38:18 -04:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
|
|
|
|
|
|
/// @file GCS_MAVLink.cpp
|
|
|
|
/// @brief Supporting bits for MAVLink.
|
|
|
|
|
|
|
|
#include "GCS_MAVLink.h"
|
|
|
|
|
2011-09-04 19:52:22 -03:00
|
|
|
BetterStream *mavlink_comm_0_port;
|
|
|
|
BetterStream *mavlink_comm_1_port;
|
2010-11-25 02:38:18 -04:00
|
|
|
|
|
|
|
// this might need to move to the flight software
|
|
|
|
mavlink_system_t mavlink_system = {7,1,0,0};
|
2011-09-17 22:03:27 -03:00
|
|
|
|
2011-10-16 04:00:12 -03:00
|
|
|
#ifdef MAVLINK10
|
2012-04-19 16:46:29 -03:00
|
|
|
# include "include/mavlink/v1.0/mavlink_helpers.h"
|
2011-10-16 04:00:12 -03:00
|
|
|
#else
|
2012-04-19 16:46:29 -03:00
|
|
|
# include "include/mavlink/v0.9/mavlink_helpers.h"
|
2011-10-16 04:00:12 -03:00
|
|
|
#endif
|
2011-09-24 09:40:07 -03:00
|
|
|
|
|
|
|
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
|
|
|
|
}
|