AP_VisualOdom: log corrected position instead of raw position

This commit is contained in:
Randy Mackay 2020-04-11 10:52:59 +09:00 committed by Andrew Tridgell
parent 6622927a23
commit 3557104787
2 changed files with 2 additions and 2 deletions

View File

@ -53,7 +53,7 @@ void AP_VisualOdom_IntelT265::handle_vision_position_estimate(uint64_t remote_ti
att.to_euler(roll, pitch, yaw);
// log sensor data
AP::logger().Write_VisualPosition(remote_time_us, time_ms, x, y, z, degrees(roll), degrees(pitch), wrap_360(degrees(yaw)), reset_counter);
AP::logger().Write_VisualPosition(remote_time_us, time_ms, pos.x, pos.y, pos.z, degrees(roll), degrees(pitch), wrap_360(degrees(yaw)), reset_counter);
// store corrected attitude for use in pre-arm checks
_attitude_last = att;

View File

@ -80,7 +80,7 @@ void AP_VisualOdom_MAV::handle_vision_position_estimate(uint64_t remote_time_us,
attitude.to_euler(roll, pitch, yaw);
// log sensor data
AP::logger().Write_VisualPosition(remote_time_us, time_ms, x, y, z, degrees(roll), degrees(pitch), degrees(yaw), reset_counter);
AP::logger().Write_VisualPosition(remote_time_us, time_ms, pos.x, pos.y, pos.z, degrees(roll), degrees(pitch), degrees(yaw), reset_counter);
// record time for health monitoring
_last_update_ms = AP_HAL::millis();