mirror of https://github.com/ArduPilot/ardupilot
APM: Fixed bug where landing_pitch wasnt initialized properly
this adds a new LAND_PITCH_CD parameter to control the landing pitch when an airspeed sensor is not being used
This commit is contained in:
parent
d6e370886f
commit
d02655ac56
|
@ -476,8 +476,6 @@ static bool takeoff_complete = true;
|
|||
static bool land_complete;
|
||||
// Altitude threshold to complete a takeoff command in autonomous modes. Centimeters
|
||||
static int32_t takeoff_altitude;
|
||||
// Pitch to hold during landing command in the no airspeed sensor case. Hundredths of a degree
|
||||
static int16_t landing_pitch;
|
||||
// Minimum pitch to hold during takeoff command execution. Hundredths of a degree
|
||||
static int16_t takeoff_pitch;
|
||||
|
||||
|
@ -1014,7 +1012,7 @@ static void update_current_flight_mode(void)
|
|||
}else{
|
||||
calc_nav_pitch(); // calculate nav_pitch just to use for calc_throttle
|
||||
calc_throttle(); // throttle based on altitude error
|
||||
nav_pitch = landing_pitch; // pitch held constant
|
||||
nav_pitch = g.land_pitch_cd; // pitch held constant
|
||||
}
|
||||
|
||||
if (land_complete) {
|
||||
|
|
|
@ -69,6 +69,7 @@ public:
|
|||
k_param_log_last_filenumber, // *** Deprecated - remove with next eeprom number change
|
||||
k_param_reset_switch_chan,
|
||||
k_param_manual_level,
|
||||
k_param_land_pitch_cd,
|
||||
|
||||
// 110: Telemetry control
|
||||
//
|
||||
|
@ -337,6 +338,7 @@ public:
|
|||
AP_Int8 reset_switch_chan;
|
||||
AP_Int8 manual_level;
|
||||
AP_Int16 airspeed_cruise_cm;
|
||||
AP_Int16 land_pitch_cd;
|
||||
AP_Int16 min_gndspeed;
|
||||
AP_Int16 pitch_trim;
|
||||
AP_Int16 RTL_altitude;
|
||||
|
@ -456,6 +458,7 @@ public:
|
|||
reset_switch_chan (0),
|
||||
manual_level (MANUAL_LEVEL),
|
||||
airspeed_cruise_cm (AIRSPEED_CRUISE_CM),
|
||||
land_pitch_cd (0),
|
||||
min_gndspeed (MIN_GNDSPEED_CM),
|
||||
pitch_trim (0),
|
||||
RTL_altitude (ALT_HOLD_HOME_CM),
|
||||
|
|
|
@ -65,6 +65,13 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
|||
// @User: Advanced
|
||||
GSCALAR(manual_level, "MANUAL_LEVEL"),
|
||||
|
||||
// @Param: land_pitch_cd
|
||||
// @DisplayName: Landing Pitch
|
||||
// @Description: Used in autoland for planes without airspeed sensors in hundredths of a degree
|
||||
// @Units: centi-Degrees
|
||||
// @User: Advanced
|
||||
GSCALAR(land_pitch_cd, "land_pitch_cd"),
|
||||
|
||||
// @Param: XTRK_GAIN_SC
|
||||
// @DisplayName: Crosstrack Gain
|
||||
// @Description: The scale between distance off the line and angle to meet the line (in Degrees * 100)
|
||||
|
|
Loading…
Reference in New Issue