MAVLink: make APM build with MAVLink 1.0 possible with arduino GUI

This commit is contained in:
Andrew Tridgell 2012-04-24 22:18:30 +10:00
parent 7866740d62
commit 9d56d28615
6 changed files with 49 additions and 17 deletions

View File

@ -28,3 +28,6 @@
*/ */
// use this to enable the new MAVLink 1.0 protocol, instead of the
// older 0.9 protocol
// #define MAVLINK10 ENABLED

View File

@ -47,13 +47,14 @@ version 2.1 of the License, or (at your option) any later version.
#include <Filter.h> // Filter library #include <Filter.h> // Filter library
#include <ModeFilter.h> // Mode Filter from Filter library #include <ModeFilter.h> // Mode Filter from Filter library
#include <AP_Relay.h> // APM relay #include <AP_Relay.h> // APM relay
#include <AP_Mount.h> // Camera/Antenna mount
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <memcheck.h> #include <memcheck.h>
// Configuration // Configuration
#include "config.h" #include "config.h"
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <AP_Mount.h> // Camera/Antenna mount
// Local modules // Local modules
#include "defines.h" #include "defines.h"
#include "Parameters.h" #include "Parameters.h"

View File

@ -8,7 +8,6 @@
#include <FastSerial.h> #include <FastSerial.h>
#include <AP_Common.h> #include <AP_Common.h>
#include <GCS_MAVLink.h>
#include <GPS.h> #include <GPS.h>
#include <Stream.h> #include <Stream.h>
#include <stdint.h> #include <stdint.h>

View File

@ -27,7 +27,7 @@ static bool mavlink_active;
static NOINLINE void send_heartbeat(mavlink_channel_t chan) static NOINLINE void send_heartbeat(mavlink_channel_t chan)
{ {
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint8_t system_status = MAV_STATE_ACTIVE; uint8_t system_status = MAV_STATE_ACTIVE;
uint32_t custom_mode = control_mode; uint32_t custom_mode = control_mode;
@ -130,7 +130,7 @@ static NOINLINE void send_fence_status(mavlink_channel_t chan)
static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops) static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops)
{ {
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
uint32_t control_sensors_present = 0; uint32_t control_sensors_present = 0;
uint32_t control_sensors_enabled; uint32_t control_sensors_enabled;
uint32_t control_sensors_health; uint32_t control_sensors_health;
@ -337,7 +337,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
static void NOINLINE send_gps_raw(mavlink_channel_t chan) static void NOINLINE send_gps_raw(mavlink_channel_t chan)
{ {
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
uint8_t fix = g_gps->status(); uint8_t fix = g_gps->status();
if (fix == GPS::GPS_OK) { if (fix == GPS::GPS_OK) {
fix = 3; fix = 3;
@ -501,6 +501,21 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
#endif // HIL_MODE != HIL_MODE_ATTITUDE #endif // HIL_MODE != HIL_MODE_ATTITUDE
#ifdef DESKTOP_BUILD #ifdef DESKTOP_BUILD
void mavlink_simstate_send(uint8_t chan,
float roll,
float pitch,
float yaw,
float xAcc,
float yAcc,
float zAcc,
float p,
float q,
float r)
{
mavlink_msg_simstate_send((mavlink_channel_t)chan,
roll, pitch, yaw, xAcc, yAcc, zAcc, p, q, r);
}
// report simulator state // report simulator state
static void NOINLINE send_simstate(mavlink_channel_t chan) static void NOINLINE send_simstate(mavlink_channel_t chan)
{ {
@ -592,7 +607,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
break; break;
case MSG_GPS_RAW: case MSG_GPS_RAW:
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
CHECK_PAYLOAD_SIZE(GPS_RAW_INT); CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
#else #else
CHECK_PAYLOAD_SIZE(GPS_RAW); CHECK_PAYLOAD_SIZE(GPS_RAW);
@ -1082,7 +1097,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break; break;
} }
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
case MAVLINK_MSG_ID_COMMAND_LONG: case MAVLINK_MSG_ID_COMMAND_LONG:
{ {
// decode // decode
@ -1272,7 +1287,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_set_mode_t packet; mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet); mavlink_msg_set_mode_decode(msg, &packet);
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) { if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// we ignore base_mode as there is no sane way to map // we ignore base_mode as there is no sane way to map
// from that bitmap to a APM flight mode. We rely on // from that bitmap to a APM flight mode. We rely on
@ -1328,7 +1343,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break; break;
} }
#ifndef MAVLINK10 #if MAVLINK10 == DISABLED
case MAVLINK_MSG_ID_SET_NAV_MODE: case MAVLINK_MSG_ID_SET_NAV_MODE:
{ {
// decode // decode
@ -1680,7 +1695,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break; break;
default: default:
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
result = MAV_MISSION_UNSUPPORTED; result = MAV_MISSION_UNSUPPORTED;
#endif #endif
break; break;
@ -1896,7 +1911,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
#if HIL_MODE != HIL_MODE_DISABLED #if HIL_MODE != HIL_MODE_DISABLED
// This is used both as a sensor and to pass the location // This is used both as a sensor and to pass the location
// in HIL_ATTITUDE mode. // in HIL_ATTITUDE mode.
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
case MAVLINK_MSG_ID_GPS_RAW_INT: case MAVLINK_MSG_ID_GPS_RAW_INT:
{ {
// decode // decode
@ -1934,7 +1949,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
airspeed = 100*packet.airspeed; airspeed = 100*packet.airspeed;
break; break;
} }
#ifdef MAVLINK10 #if MAVLINK10 == ENABLED
case MAVLINK_MSG_ID_HIL_STATE: case MAVLINK_MSG_ID_HIL_STATE:
{ {
mavlink_hil_state_t packet; mavlink_hil_state_t packet;
@ -2257,3 +2272,19 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0); mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
} }
} }
// this code was moved from libraries/GCS_MAVLink to allow compile
// time selection of MAVLink 1.0
BetterStream *mavlink_comm_0_port;
BetterStream *mavlink_comm_1_port;
mavlink_system_t mavlink_system = {7,1,0,0};
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
}

View File

@ -25,13 +25,13 @@ apm2beta:
make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DAPM2_BETA_HARDWARE" make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DAPM2_BETA_HARDWARE"
mavlink10: mavlink10:
make -f Makefile EXTRAFLAGS="-DMAVLINK10" make -f Makefile EXTRAFLAGS="-DMAVLINK10=1"
sitl: sitl:
make -f ../libraries/Desktop/Makefile.desktop make -f ../libraries/Desktop/Makefile.desktop
sitl-mavlink10: sitl-mavlink10:
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMAVLINK10" make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMAVLINK10=1"
sitl-mount: sitl-mount:
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMOUNT=ENABLED" make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMOUNT=ENABLED"

View File

@ -95,8 +95,6 @@
#define RELAY_TOGGLE 5 #define RELAY_TOGGLE 5
#define STOP_REPEAT 10 #define STOP_REPEAT 10
#define MAV_CMD_CONDITION_YAW 23
// GCS Message ID's // GCS Message ID's
/// NOTE: to ensure we never block on sending MAVLink messages /// NOTE: to ensure we never block on sending MAVLink messages
/// please keep each MSG_ to a single MAVLink message. If need be /// please keep each MSG_ to a single MAVLink message. If need be