mirror of https://github.com/ArduPilot/ardupilot
AP_L1_Control: use projected position for turns
This commit is contained in:
parent
9c88872ad0
commit
df8e8c64e8
|
@ -97,7 +97,7 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
|
|||
float K_L1 = 4.0f * _L1_damping * _L1_damping;
|
||||
|
||||
// Get current position and velocity
|
||||
_ahrs->get_position(_current_loc);
|
||||
_ahrs->get_projected_position(_current_loc);
|
||||
|
||||
// update _target_bearing_cd
|
||||
_target_bearing_cd = get_bearing_cd(_current_loc, next_WP);
|
||||
|
@ -197,7 +197,7 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius
|
|||
float K_L1 = 4.0f * _L1_damping * _L1_damping;
|
||||
|
||||
//Get current position and velocity
|
||||
_ahrs->get_position(_current_loc);
|
||||
_ahrs->get_projected_position(_current_loc);
|
||||
|
||||
// update _target_bearing_cd
|
||||
_target_bearing_cd = get_bearing_cd(_current_loc, center_WP);
|
||||
|
|
Loading…
Reference in New Issue