mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 23:18:28 -04:00
AP_Follow: use GCS_SEND_TEXT rather than gcs().send_text
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
fa4e90a3bb
commit
4d24e7bbf0
@ -488,13 +488,13 @@ void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned)
|
|||||||
if ((_offset_type == AP_FOLLOW_OFFSET_TYPE_RELATIVE) && get_target_heading_deg(target_heading_deg)) {
|
if ((_offset_type == AP_FOLLOW_OFFSET_TYPE_RELATIVE) && get_target_heading_deg(target_heading_deg)) {
|
||||||
// rotate offsets from north facing to vehicle's perspective
|
// rotate offsets from north facing to vehicle's perspective
|
||||||
_offset.set(rotate_vector(-dist_vec_ned, -target_heading_deg));
|
_offset.set(rotate_vector(-dist_vec_ned, -target_heading_deg));
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Relative follow offset loaded");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Relative follow offset loaded");
|
||||||
} else {
|
} else {
|
||||||
// initialise offset in NED frame
|
// initialise offset in NED frame
|
||||||
_offset.set(-dist_vec_ned);
|
_offset.set(-dist_vec_ned);
|
||||||
// ensure offset_type used matches frame of offsets saved
|
// ensure offset_type used matches frame of offsets saved
|
||||||
_offset_type.set(AP_FOLLOW_OFFSET_TYPE_NED);
|
_offset_type.set(AP_FOLLOW_OFFSET_TYPE_NED);
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "N-E-D follow offset loaded");
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "N-E-D follow offset loaded");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user