mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AC_AttitudeControl: Remove unused takeoff jump #define
This commit is contained in:
parent
f3770432f9
commit
14882bc6a8
@ -254,7 +254,7 @@ void AC_PosControl::init_takeoff()
|
|||||||
{
|
{
|
||||||
const Vector3f& curr_pos = _inav.get_position();
|
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 feedforward to avoid jump
|
||||||
freeze_ff_z();
|
freeze_ff_z();
|
||||||
|
@ -22,7 +22,6 @@
|
|||||||
#define POSCONTROL_STOPPING_DIST_Z_MAX 200.0f // max stopping distance vertically
|
#define POSCONTROL_STOPPING_DIST_Z_MAX 200.0f // max stopping distance vertically
|
||||||
// should be 1.5 times larger than POSCONTROL_ACCELERATION.
|
// 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
|
// 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 500.0f // default horizontal speed in cm/s
|
||||||
#define POSCONTROL_SPEED_DOWN -150.0f // default descent rate in cm/s
|
#define POSCONTROL_SPEED_DOWN -150.0f // default descent rate in cm/s
|
||||||
|
Loading…
Reference in New Issue
Block a user