mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: speed-up and down parameter min to 10cm/s
This commit is contained in:
parent
63dc5121bd
commit
40cceea8b8
|
@ -28,7 +28,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = {
|
||||||
// @DisplayName: Waypoint Climb Speed Target
|
// @DisplayName: Waypoint Climb Speed Target
|
||||||
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission
|
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission
|
||||||
// @Units: cm/s
|
// @Units: cm/s
|
||||||
// @Range: 0 1000
|
// @Range: 10 1000
|
||||||
// @Increment: 50
|
// @Increment: 50
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("SPEED_UP", 2, AC_WPNav, _wp_speed_up_cms, WPNAV_WP_SPEED_UP),
|
AP_GROUPINFO("SPEED_UP", 2, AC_WPNav, _wp_speed_up_cms, WPNAV_WP_SPEED_UP),
|
||||||
|
@ -37,7 +37,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = {
|
||||||
// @DisplayName: Waypoint Descent Speed Target
|
// @DisplayName: Waypoint Descent Speed Target
|
||||||
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission
|
// @Description: Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission
|
||||||
// @Units: cm/s
|
// @Units: cm/s
|
||||||
// @Range: 0 500
|
// @Range: 10 500
|
||||||
// @Increment: 10
|
// @Increment: 10
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("SPEED_DN", 3, AC_WPNav, _wp_speed_down_cms, WPNAV_WP_SPEED_DOWN),
|
AP_GROUPINFO("SPEED_DN", 3, AC_WPNav, _wp_speed_down_cms, WPNAV_WP_SPEED_DOWN),
|
||||||
|
|
Loading…
Reference in New Issue