diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 1c6d6c5886..b6fbc6b5eb 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -627,15 +627,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 02a14311ee..07a3cce18a 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -265,3 +265,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; }