mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_L1_Control: no need to project position for lag
now handled by AHRS
This commit is contained in:
parent
91cbad52a1
commit
b9128a932f
@ -124,11 +124,6 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
|
|||||||
|
|
||||||
Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
|
Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
|
||||||
|
|
||||||
// update the position for lag. This helps especially for rovers
|
|
||||||
// where waypoints may be very close together
|
|
||||||
Vector2f lag_offset = _groundspeed_vector * _ahrs.get_position_lag();
|
|
||||||
location_offset(_current_loc, lag_offset.x, lag_offset.y);
|
|
||||||
|
|
||||||
// update _target_bearing_cd
|
// update _target_bearing_cd
|
||||||
_target_bearing_cd = get_bearing_cd(_current_loc, next_WP);
|
_target_bearing_cd = get_bearing_cd(_current_loc, next_WP);
|
||||||
|
|
||||||
@ -229,11 +224,6 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius
|
|||||||
|
|
||||||
Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
|
Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
|
||||||
|
|
||||||
// update the position for lag. This helps especially for rovers
|
|
||||||
// where waypoints may be very close together
|
|
||||||
Vector2f lag_offset = _groundspeed_vector * _ahrs.get_position_lag();
|
|
||||||
location_offset(_current_loc, lag_offset.x, lag_offset.y);
|
|
||||||
|
|
||||||
//Calculate groundspeed
|
//Calculate groundspeed
|
||||||
float groundSpeed = max(_groundspeed_vector.length() , 1.0f);
|
float groundSpeed = max(_groundspeed_vector.length() , 1.0f);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user