Copter: convert RTL_ALT to int32

This commit is contained in:
Josh Henderson 2021-09-15 00:00:54 -04:00 committed by Randy Mackay
parent 05b07468af
commit 24b6f024ea
4 changed files with 8 additions and 4 deletions

View File

@ -109,7 +109,7 @@ const AP_Param::Info Copter::var_info[] = {
// @DisplayName: RTL Altitude
// @Description: The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude.
// @Units: cm
// @Range: 200 8000
// @Range: 200 300000
// @Increment: 1
// @User: Standard
GSCALAR(rtl_altitude, "RTL_ALT", RTL_ALT),
@ -1186,6 +1186,10 @@ void Copter::load_parameters(void)
// convert fs_options parameters
convert_fs_options_params();
#if MODE_RTL_ENABLED == ENABLED
g.rtl_altitude.convert_parameter_width(AP_PARAM_INT16);
#endif
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
// setup AP_Param frame type flags

View File

@ -394,7 +394,7 @@ public:
AP_Float pilot_takeoff_alt;
#if MODE_RTL_ENABLED == ENABLED
AP_Int16 rtl_altitude;
AP_Int32 rtl_altitude;
AP_Int16 rtl_speed_cms;
AP_Float rtl_cone_slope;
AP_Int16 rtl_alt_final;

View File

@ -144,7 +144,7 @@ void AP_Avoidance_Copter::set_mode_else_try_RTL_else_LAND(Mode::Number mode)
}
}
int16_t AP_Avoidance_Copter::get_altitude_minimum() const
int32_t AP_Avoidance_Copter::get_altitude_minimum() const
{
#if MODE_RTL_ENABLED == ENABLED
// do not descend if below RTL alt

View File

@ -20,7 +20,7 @@ private:
void set_mode_else_try_RTL_else_LAND(Mode::Number mode);
// get minimum limit altitude allowed on descend
int16_t get_altitude_minimum() const;
int32_t get_altitude_minimum() const;
protected:
// override avoidance handler