diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp index b0974348e1..5519f86d45 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp @@ -36,6 +36,7 @@ bool AP_VisualOdom_Backend::healthy() const return ((AP_HAL::millis() - _last_update_ms) < AP_VISUALODOM_TIMEOUT_MS); } +#if HAL_GCS_ENABLED // consume vision_position_delta mavlink messages void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_message_t &msg) { @@ -69,6 +70,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa position_delta, packet.confidence); } +#endif // HAL_GCS_ENABLED // returns the system time of the last reset if reset_counter has not changed // updates the reset timestamp to the current system time if the reset_counter has changed diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h index b17eef76e7..ce2033ca4c 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h @@ -27,8 +27,10 @@ public: // return true if sensor is basically healthy (we are receiving data) bool healthy() const; +#if HAL_GCS_ENABLED // consume vision_position_delta mavlink messages void handle_vision_position_delta_msg(const mavlink_message_t &msg); +#endif // consume vision pose estimate data and send to EKF. distances in meters virtual void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) = 0;