diff --git a/libraries/AP_VisualOdom/AP_VisualOdom.cpp b/libraries/AP_VisualOdom/AP_VisualOdom.cpp index 1aa8dfb7b5..485a367f2a 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom.cpp @@ -156,6 +156,7 @@ bool AP_VisualOdom::healthy() const return _driver->healthy(); } +#if HAL_GCS_ENABLED // consume vision_position_delta mavlink messages void AP_VisualOdom::handle_vision_position_delta_msg(const mavlink_message_t &msg) { @@ -169,6 +170,7 @@ void AP_VisualOdom::handle_vision_position_delta_msg(const mavlink_message_t &ms _driver->handle_vision_position_delta_msg(msg); } } +#endif // general purpose method to consume position estimate data and send to EKF // distances in meters, roll, pitch and yaw are in radians diff --git a/libraries/AP_VisualOdom/AP_VisualOdom.h b/libraries/AP_VisualOdom/AP_VisualOdom.h index 88bac3ac8c..20691d41c5 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom.h @@ -27,6 +27,7 @@ #include #include #include +#include class AP_VisualOdom_Backend; @@ -80,8 +81,10 @@ public: // return yaw measurement noise in rad float get_yaw_noise() const { return _yaw_noise; } +#if HAL_GCS_ENABLED // consume vision_position_delta mavlink messages void handle_vision_position_delta_msg(const mavlink_message_t &msg); +#endif // general purpose methods to consume position estimate data and send to EKF // distances in meters, roll, pitch and yaw are in radians