Copter: #define for initial altitude jump during take-off
Developers can add a line like to APM_Config.h to reduce the initial jump when taking off in Loiter or AltHold flightmodes: #define ALT_HOLD_TAKEOFF_JUMP 0
This commit is contained in:
parent
072b231c3f
commit
653a5036ae
@ -985,7 +985,7 @@ set_throttle_takeoff()
|
||||
{
|
||||
// set alt target
|
||||
if (controller_desired_alt < current_loc.alt) {
|
||||
controller_desired_alt = current_loc.alt + 20;
|
||||
controller_desired_alt = current_loc.alt + ALT_HOLD_TAKEOFF_JUMP;
|
||||
}
|
||||
// clear i term from acceleration controller
|
||||
if (g.pid_throttle_accel.get_integrator() < 0) {
|
||||
|
@ -920,7 +920,7 @@
|
||||
// Autopilot rotate rate limits
|
||||
//
|
||||
#ifndef AUTO_YAW_SLEW_RATE
|
||||
# define AUTO_YAW_SLEW_RATE 60 // degrees/sec
|
||||
# define AUTO_YAW_SLEW_RATE 60 // degrees/sec
|
||||
#endif
|
||||
|
||||
|
||||
@ -928,11 +928,15 @@
|
||||
// Throttle control gains
|
||||
//
|
||||
#ifndef THROTTLE_CRUISE
|
||||
# define THROTTLE_CRUISE 450 //
|
||||
# define THROTTLE_CRUISE 450 // default estimate of throttle required for vehicle to maintain a hover
|
||||
#endif
|
||||
|
||||
#ifndef THR_MID
|
||||
# define THR_MID 500 // Throttle output (0 ~ 1000) when throttle stick is in mid position
|
||||
# define THR_MID 500 // Throttle output (0 ~ 1000) when throttle stick is in mid position
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_TAKEOFF_JUMP
|
||||
# define ALT_HOLD_TAKEOFF_JUMP 20 // jump in altitude target when taking off in Loiter or AltHold flight modes
|
||||
#endif
|
||||
|
||||
#ifndef ALT_HOLD_P
|
||||
@ -964,7 +968,6 @@
|
||||
#ifndef PILOT_VELZ_MAX
|
||||
# define PILOT_VELZ_MAX 250 // maximum vertical velocity in cm/s
|
||||
#endif
|
||||
#define ACCELERATION_MAX_Z 750 // maximum veritcal acceleration in cm/s/s
|
||||
|
||||
// max distance in cm above or below current location that will be used for the alt target when transitioning to alt-hold mode
|
||||
#ifndef ALT_HOLD_INIT_MAX_OVERSHOOT
|
||||
|
Loading…
Reference in New Issue
Block a user