mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: inav use _xy()
This commit is contained in:
parent
6b871fba55
commit
c6dd39773d
|
@ -2331,7 +2331,7 @@ void QuadPlane::vtol_position_controller(void)
|
|||
|
||||
// reset position controller xy target to current position
|
||||
// because we only want velocity control (no position control)
|
||||
const Vector3f& curr_pos = inertial_nav.get_position();
|
||||
const Vector2f& curr_pos = inertial_nav.get_position_xy();
|
||||
pos_control->set_pos_target_xy_cm(curr_pos.x, curr_pos.y);
|
||||
pos_control->set_accel_desired_xy_cmss(Vector2f());
|
||||
|
||||
|
|
Loading…
Reference in New Issue