Skip to content

Commit

Permalink
AC_PosControl: hack to remove jump -- do not merge
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Aug 19, 2024
1 parent 11e78f3 commit 15823bd
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AC_AttitudeControl/AC_PosControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -538,12 +538,12 @@ void AC_PosControl::init_xy_controller()
_accel_target.xy().limit_length(accel_max);

// initialise horizontal offsets
_xy_offset_type = XYOffsetType::POSITION;
/*_xy_offset_type = XYOffsetType::POSITION;
_pos_offset_target.xy().zero();
_pos_offset.xy().zero();
_vel_offset_target.zero();
_vel_offset.xy().zero();
_accel_offset.xy().zero();
_accel_offset.xy().zero();*/

// initialise I terms from lean angles
_pid_vel_xy.reset_filter();
Expand Down

0 comments on commit 15823bd

Please sign in to comment.