mirror of https://github.com/ArduPilot/ardupilot
Copter: disable RTL option
This commit is contained in:
parent
d97a81bfea
commit
621fa857b7
|
@ -158,6 +158,13 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @Increment: 1000
|
||||
// @User: Standard
|
||||
GSCALAR(rtl_loiter_time, "RTL_LOIT_TIME", RTL_LOITER_TIME),
|
||||
|
||||
// @Param: RTL_ALT_TYPE
|
||||
// @DisplayName: RTL mode altitude type
|
||||
// @Description: RTL altitude type. Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database
|
||||
// @Values: 0:Relative to Home, 1:Terrain
|
||||
// @User: Standard
|
||||
GSCALAR(rtl_alt_type, "RTL_ALT_TYPE", 0),
|
||||
#endif
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
|
@ -735,13 +742,6 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED),
|
||||
#endif
|
||||
|
||||
// @Param: RTL_ALT_TYPE
|
||||
// @DisplayName: RTL mode altitude type
|
||||
// @Description: RTL altitude type. Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database
|
||||
// @Values: 0:Relative to Home, 1:Terrain
|
||||
// @User: Standard
|
||||
GSCALAR(rtl_alt_type, "RTL_ALT_TYPE", 0),
|
||||
|
||||
#if OSD_ENABLED || OSD_PARAM_ENABLED
|
||||
// @Group: OSD
|
||||
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
|
||||
|
|
|
@ -392,9 +392,16 @@ public:
|
|||
AP_Int16 throttle_behavior;
|
||||
AP_Float pilot_takeoff_alt;
|
||||
|
||||
#if MODE_RTL_ENABLED == ENABLED
|
||||
AP_Int16 rtl_altitude;
|
||||
AP_Int16 rtl_speed_cms;
|
||||
AP_Float rtl_cone_slope;
|
||||
AP_Int16 rtl_alt_final;
|
||||
AP_Int16 rtl_climb_min; // rtl minimum climb in cm
|
||||
AP_Int32 rtl_loiter_time;
|
||||
AP_Int8 rtl_alt_type;
|
||||
#endif
|
||||
|
||||
#if RANGEFINDER_ENABLED == ENABLED
|
||||
AP_Float rangefinder_gain;
|
||||
#endif
|
||||
|
@ -403,8 +410,6 @@ public:
|
|||
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
|
||||
|
||||
AP_Int8 super_simple;
|
||||
AP_Int16 rtl_alt_final;
|
||||
AP_Int16 rtl_climb_min; // rtl minimum climb in cm
|
||||
|
||||
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
|
||||
|
||||
|
@ -415,7 +420,6 @@ public:
|
|||
|
||||
// Waypoints
|
||||
//
|
||||
AP_Int32 rtl_loiter_time;
|
||||
AP_Int16 land_speed;
|
||||
AP_Int16 land_speed_high;
|
||||
AP_Int16 pilot_speed_up; // maximum vertical ascending velocity the pilot may request
|
||||
|
@ -457,8 +461,6 @@ public:
|
|||
AP_Enum<ModeThrow::PreThrowMotorState> throw_motor_start;
|
||||
#endif
|
||||
|
||||
AP_Int8 rtl_alt_type;
|
||||
|
||||
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
|
||||
|
||||
// Acro parameters
|
||||
|
|
Loading…
Reference in New Issue