From 1c046fa49f3ab07c512a7b3831eba9f177c7c87c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 18 Apr 2013 22:32:00 +0900 Subject: [PATCH] AC_WPNav: increase max descent speed to 1.5m/s --- libraries/AC_WPNav/AC_WPNav.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index b5d25b9027..03ae8c09b3 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -31,7 +31,7 @@ #define WPNAV_WP_RADIUS 200.0f // default waypoint radius in cm #define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity -#define WPNAV_WP_SPEED_DOWN 125.0f // default maximum descent velocity +#define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity #define WPNAV_ALT_HOLD_P 2.0f // hard coded estimate of throttle controller's altitude hold's P gain. To-Do: retrieve gain from throttle controller #define WPNAV_ALT_HOLD_ACCEL_MAX 250.0f // hard coded estimate of throttle controller's maximum acceleration in cm/s. To-Do: retrieve from throttle controller