GCS_MAVLink: use APM_BUILD_DELEGATES

This commit is contained in:
Andrew Tridgell 2015-05-13 18:33:26 +10:00
parent f8aef57ec3
commit 84726e4a3a

View File

@ -70,7 +70,7 @@ class GCS_MAVLINK
{
public:
GCS_MAVLINK();
#if APM_BUILD_TYPE(APM_BUILD_APMrover2)
#if APM_BUILD_DELEGATES
typedef DELEGATE_FUNCTION1(void, AP_HAL::UARTDriver*) run_cli_fn;
#else
typedef void (*run_cli_fn)(AP_HAL::UARTDriver *);
@ -299,7 +299,7 @@ private:
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio);
void handle_serial_control(mavlink_message_t *msg, AP_GPS &gps);
void lock_channel(mavlink_channel_t chan, bool lock);
#if APM_BUILD_TYPE(APM_BUILD_APMrover2)
#if APM_BUILD_DELEGATES
typedef DELEGATE_FUNCTION1(bool, uint8_t) set_mode_fn;
#else
typedef bool (*set_mode_fn)(uint8_t);