diff --git a/libraries/AP_DAL/AP_DAL_VisualOdom.cpp b/libraries/AP_DAL/AP_DAL_VisualOdom.cpp index d24c04a184..e5824a5c56 100644 --- a/libraries/AP_DAL/AP_DAL_VisualOdom.cpp +++ b/libraries/AP_DAL/AP_DAL_VisualOdom.cpp @@ -14,7 +14,10 @@ void AP_DAL_VisualOdom::start_frame() const log_RVOH old = RVOH; RVOH.ptr_is_nullptr = (vo == nullptr); if (vo != nullptr) { + RVOH.pos_offset = vo->get_pos_offset(); + RVOH.delay_ms = vo->get_delay_ms(); RVOH.healthy = vo->healthy(); + RVOH.enabled = vo->enabled(); } WRITE_REPLAY_BLOCK_IFCHANGED(RVOH, RVOH, old);