mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: convert LAND_PITCH_CD to LAND_PITCH_DEG
This commit is contained in:
parent
2c73c56403
commit
ee884ab137
|
@ -202,7 +202,7 @@ float Plane::stabilize_pitch_get_pitch_out()
|
|||
return pitch_out;
|
||||
}
|
||||
#endif
|
||||
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_CD if flight option FORCE_FLARE_ATTITUDE is set
|
||||
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_DEG if flight option FORCE_FLARE_ATTITUDE is set
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
const bool quadplane_in_transition = quadplane.in_transition();
|
||||
#else
|
||||
|
|
|
@ -1313,7 +1313,6 @@ static const AP_Param::ConversionInfo conversion_table[] = {
|
|||
|
||||
{ Parameters::k_param_land_slope_recalc_shallow_threshold,0,AP_PARAM_FLOAT, "LAND_SLOPE_RCALC" },
|
||||
{ Parameters::k_param_land_slope_recalc_steep_threshold_to_abort,0,AP_PARAM_FLOAT, "LAND_ABORT_DEG" },
|
||||
{ Parameters::k_param_land_pitch_cd, 0, AP_PARAM_INT16, "LAND_PITCH_CD" },
|
||||
{ Parameters::k_param_land_flare_alt, 0, AP_PARAM_FLOAT, "LAND_FLARE_ALT" },
|
||||
{ Parameters::k_param_land_flare_sec, 0, AP_PARAM_FLOAT, "LAND_FLARE_SEC" },
|
||||
{ Parameters::k_param_land_pre_flare_sec, 0, AP_PARAM_FLOAT, "LAND_PF_SEC" },
|
||||
|
@ -1556,5 +1555,7 @@ void Plane::load_parameters(void)
|
|||
aparm.pitch_limit_min.convert_centi_parameter(AP_PARAM_INT16);
|
||||
aparm.roll_limit.convert_centi_parameter(AP_PARAM_INT16);
|
||||
|
||||
landing.convert_parameters();
|
||||
|
||||
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue