mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: use vector.xy().length() instead of norm(x,y)
This commit is contained in:
parent
1da21c3b21
commit
d6d9577f27
@ -73,7 +73,7 @@ float Sub::get_roi_yaw()
|
||||
float Sub::get_look_ahead_yaw()
|
||||
{
|
||||
const Vector3f& vel = inertial_nav.get_velocity();
|
||||
float speed = norm(vel.x,vel.y);
|
||||
const float speed = vel.xy().length();
|
||||
// Commanded Yaw to automatically look ahead.
|
||||
if (position_ok() && (speed > YAW_LOOK_AHEAD_MIN_SPEED)) {
|
||||
yaw_look_ahead_bearing = degrees(atan2f(vel.y,vel.x))*100.0f;
|
||||
|
Loading…
Reference in New Issue
Block a user