AP_VisualOdom: pass velocity error to logger

This commit is contained in:
Randy Mackay 2020-05-29 10:29:32 +09:00
parent 08f6b2128e
commit 79901ffc1b
2 changed files with 2 additions and 2 deletions

View File

@ -75,7 +75,7 @@ void AP_VisualOdom_IntelT265::handle_vision_speed_estimate(uint64_t remote_time_
// record time for health monitoring // record time for health monitoring
_last_update_ms = AP_HAL::millis(); _last_update_ms = AP_HAL::millis();
AP::logger().Write_VisualVelocity(remote_time_us, time_ms, vel_corrected, reset_counter); AP::logger().Write_VisualVelocity(remote_time_us, time_ms, vel_corrected, _frontend.get_vel_noise(), reset_counter);
} }
// apply rotation and correction to position // apply rotation and correction to position

View File

@ -61,7 +61,7 @@ void AP_VisualOdom_MAV::handle_vision_speed_estimate(uint64_t remote_time_us, ui
// record time for health monitoring // record time for health monitoring
_last_update_ms = AP_HAL::millis(); _last_update_ms = AP_HAL::millis();
AP::logger().Write_VisualVelocity(remote_time_us, time_ms, vel, reset_counter); AP::logger().Write_VisualVelocity(remote_time_us, time_ms, vel, _frontend.get_vel_noise(), reset_counter);
} }
#endif #endif