diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp index 5519f86d45..568a4b6a01 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp @@ -56,6 +56,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa // send to EKF const float time_delta_sec = packet.time_delta_usec * 1.0E-6; +#if AP_AHRS_ENABLED AP::ahrs().writeBodyFrameOdom(packet.confidence, position_delta, angle_delta, @@ -63,6 +64,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa now_ms, _frontend.get_delay_ms(), _frontend.get_pos_offset()); +#endif // log sensor data Write_VisualOdom(time_delta_sec,