From deb0fdccc8cfd616a6c8180c198c81c4ca0b8403 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 4 Nov 2019 11:42:37 +1100 Subject: [PATCH] Tracker: move all dummy methods to system.cpp MAVLink makes less sense than this --- AntennaTracker/GCS_Mavlink.cpp | 12 ------------ AntennaTracker/system.cpp | 15 +++++++++++++++ 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 1edbdafe31..6fb7e46c67 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -668,15 +668,3 @@ void GCS_MAVLINK_Tracker::send_global_position_int() 0, // Z speed cm/s (+ve Down) tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree } - - -/* dummy methods to avoid having to link against AP_Camera */ -void AP_Camera::control_msg(const mavlink_message_t &) {} -void AP_Camera::configure(float, float, float, float, float, float, float) {} -void AP_Camera::control(float, float, float, float, float, float) {} -void AP_Camera::send_feedback(mavlink_channel_t chan) {} -/* end dummy methods to avoid having to link against AP_Camera */ - -// dummy method to avoid linking AFS -bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {return false;} -AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; } diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index cd90e03803..75d3ea40ba 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -264,3 +264,18 @@ bool Tracker::should_log(uint32_t mask) } return true; } + + +#include +#include + +/* dummy methods to avoid having to link against AP_Camera */ +void AP_Camera::control_msg(const mavlink_message_t &) {} +void AP_Camera::configure(float, float, float, float, float, float, float) {} +void AP_Camera::control(float, float, float, float, float, float) {} +void AP_Camera::send_feedback(mavlink_channel_t chan) {} +/* end dummy methods to avoid having to link against AP_Camera */ + +// dummy method to avoid linking AFS +bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {return false;} +AP_AdvancedFailsafe *AP::advancedfailsafe() { return nullptr; }