mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: add RTL_SPEED parameter
This commit is contained in:
parent
9b82b2200c
commit
5086168b03
@ -128,6 +128,15 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(rtl_altitude, "RTL_ALT", RTL_ALT),
|
||||
|
||||
// @Param: RTL_SPEED
|
||||
// @DisplayName: RTL speed
|
||||
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally while flying home. If this is set to zero, WPNAV_SPEED will be used instead.
|
||||
// @Units: cm/s
|
||||
// @Range: 0 2000
|
||||
// @Increment: 50
|
||||
// @User: Standard
|
||||
GSCALAR(rtl_speed_cms, "RTL_SPEED", 0),
|
||||
|
||||
// @Param: RNGFND_GAIN
|
||||
// @DisplayName: Rangefinder gain
|
||||
// @Description: Used to adjust the speed with which the target altitude is changed when objects are sensed below the copter
|
||||
|
@ -375,6 +375,7 @@ public:
|
||||
AP_Float pilot_takeoff_alt;
|
||||
|
||||
AP_Int16 rtl_altitude;
|
||||
AP_Int16 rtl_speed_cms;
|
||||
AP_Float sonar_gain;
|
||||
|
||||
AP_Int8 failsafe_battery_enabled; // battery failsafe enabled
|
||||
|
@ -84,6 +84,11 @@ void Copter::rtl_climb_start()
|
||||
// initialise waypoint and spline controller
|
||||
wp_nav.wp_and_spline_init();
|
||||
|
||||
// RTL_SPEED == 0 means use WPNAV_SPEED
|
||||
if (!is_zero(g.rtl_speed_cms)) {
|
||||
wp_nav.set_speed_xy(g.rtl_speed_cms);
|
||||
}
|
||||
|
||||
// get horizontal stopping point
|
||||
Vector3f destination;
|
||||
wp_nav.get_wp_stopping_point_xy(destination);
|
||||
|
Loading…
Reference in New Issue
Block a user