mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_VisualOdom: log corrected position instead of raw position
This commit is contained in:
parent
6622927a23
commit
3557104787
@ -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;
|
||||
|
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user