Skip to content

Commit

Permalink
AC_PosControl: fix ekf-z-reset
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Sep 28, 2024
1 parent 5ac73bf commit 8d66d4b
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AC_AttitudeControl/AC_PosControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1529,7 +1529,7 @@ void AC_PosControl::handle_ekf_z_reset()

// To zero real position shift during relative position modes like Loiter, PosHold, Guided velocity and accleration control.
_pos_target.z = _inav.get_position_z_up_cm() + _p_pos_z.get_error();
_pos_desired.z = _pos_target.z - (_pos_offset.z - _pos_terrain);
_pos_desired.z = _pos_target.z - (_pos_offset.z + _pos_terrain);
_vel_target.z = _inav.get_velocity_z_up_cms() + _pid_vel_z.get_error();
_vel_desired.z = _vel_target.z - (_vel_offset.z + _vel_terrain);

Expand Down

0 comments on commit 8d66d4b

Please sign in to comment.