AP_VisualOdom: use GCS_SEND_TEXT rather than gcs().send_text

Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
Peter Barker 2024-08-07 13:17:22 +10:00 committed by Andrew Tridgell
parent bfd97bf0cd
commit 7c1d37f374
1 changed files with 2 additions and 2 deletions

View File

@ -192,7 +192,7 @@ void AP_VisualOdom_IntelT265::align_yaw(const Vector3f &position, const Quaterni
// trim yaw by difference between ahrs and sensor yaw // trim yaw by difference between ahrs and sensor yaw
const float yaw_trim_orig = _yaw_trim; const float yaw_trim_orig = _yaw_trim;
_yaw_trim = wrap_2PI(yaw_rad - sens_yaw); _yaw_trim = wrap_2PI(yaw_rad - sens_yaw);
gcs().send_text(MAV_SEVERITY_INFO, "VisOdom: yaw shifted %d to %d deg", GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VisOdom: yaw shifted %d to %d deg",
(int)degrees(_yaw_trim - yaw_trim_orig), (int)degrees(_yaw_trim - yaw_trim_orig),
(int)wrap_360(degrees(sens_yaw + _yaw_trim))); (int)wrap_360(degrees(sens_yaw + _yaw_trim)));
@ -349,7 +349,7 @@ void AP_VisualOdom_IntelT265::handle_voxl_camera_reset_jump(const Vector3f &sens
} }
// warng user of reset // warng user of reset
gcs().send_text(MAV_SEVERITY_WARNING, "VisOdom: reset"); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "VisOdom: reset");
// align sensor yaw to match current yaw estimate // align sensor yaw to match current yaw estimate
align_yaw_to_ahrs(sensor_pos, sensor_att); align_yaw_to_ahrs(sensor_pos, sensor_att);