Browse Source

AC_AttitudeControl: Remove unused takeoff jump #define

mission-4.1.18
Robert Lefebvre 10 years ago committed by Randy Mackay
parent
commit
14882bc6a8
  1. 2
      libraries/AC_AttitudeControl/AC_PosControl.cpp
  2. 1
      libraries/AC_AttitudeControl/AC_PosControl.h

2
libraries/AC_AttitudeControl/AC_PosControl.cpp

@ -254,7 +254,7 @@ void AC_PosControl::init_takeoff() @@ -254,7 +254,7 @@ void AC_PosControl::init_takeoff()
{
const Vector3f& curr_pos = _inav.get_position();
_pos_target.z = curr_pos.z + POSCONTROL_TAKEOFF_JUMP_CM;
_pos_target.z = curr_pos.z;
// freeze feedforward to avoid jump
freeze_ff_z();

1
libraries/AC_AttitudeControl/AC_PosControl.h

@ -22,7 +22,6 @@ @@ -22,7 +22,6 @@
#define POSCONTROL_STOPPING_DIST_Z_MAX 200.0f // max stopping distance vertically
// should be 1.5 times larger than POSCONTROL_ACCELERATION.
// max acceleration = max lean angle * 980 * pi / 180. i.e. 23deg * 980 * 3.141 / 180 = 393 cm/s/s
#define POSCONTROL_TAKEOFF_JUMP_CM 0.0f // during take-off altitude target is set to current altitude + this value
#define POSCONTROL_SPEED 500.0f // default horizontal speed in cm/s
#define POSCONTROL_SPEED_DOWN -150.0f // default descent rate in cm/s

Loading…
Cancel
Save