mirror of https://github.com/ArduPilot/ardupilot
Tracker: move all dummy methods to system.cpp
MAVLink makes less sense than this
This commit is contained in:
parent
099067dbc9
commit
5bc43dd3bd
|
@ -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; }
|
||||
|
|
|
@ -265,3 +265,18 @@ bool Tracker::should_log(uint32_t mask)
|
|||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
#include <AP_Camera/AP_Camera.h>
|
||||
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
|
||||
|
||||
/* 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; }
|
||||
|
|
Loading…
Reference in New Issue