From 9e866449e16da9208b9ec3cead6871d97026a7c3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 3 Sep 2021 12:58:50 +0900 Subject: [PATCH] AC_WPNav: move definitions to .cpp file --- libraries/AC_WPNav/AC_WPNav.cpp | 10 ++++++++++ libraries/AC_WPNav/AC_WPNav.h | 12 ------------ 2 files changed, 10 insertions(+), 12 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 0074a6ee40..b69ebeeff2 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -3,6 +3,16 @@ extern const AP_HAL::HAL& hal; +// maximum velocities and accelerations +#define WPNAV_ACCELERATION 250.0f // maximum horizontal acceleration in cm/s/s that wp navigation will request +#define WPNAV_WP_SPEED 1000.0f // default horizontal speed between waypoints in cm/s +#define WPNAV_WP_SPEED_MIN 20.0f // minimum horizontal speed between waypoints in cm/s +#define WPNAV_WP_RADIUS 200.0f // default waypoint radius in cm +#define WPNAV_WP_RADIUS_MIN 5.0f // minimum waypoint radius in cm +#define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity +#define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity +#define WPNAV_WP_ACCEL_Z_DEFAULT 100.0f // default vertical acceleration between waypoints in cm/s/s + const AP_Param::GroupInfo AC_WPNav::var_info[] = { // index 0 was used for the old orientation matrix diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index 186a52a25c..87bce8d2d2 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -12,18 +12,6 @@ #include #include // Stop at fence library -// maximum velocities and accelerations -#define WPNAV_ACCELERATION 250.0f // maximum horizontal acceleration in cm/s/s that wp navigation will request -#define WPNAV_WP_SPEED 1000.0f // default horizontal speed between waypoints in cm/s -#define WPNAV_WP_SPEED_MIN 20.0f // minimum horizontal speed between waypoints in cm/s -#define WPNAV_WP_RADIUS 200.0f // default waypoint radius in cm -#define WPNAV_WP_RADIUS_MIN 5.0f // minimum waypoint radius in cm - -#define WPNAV_WP_SPEED_UP 250.0f // default maximum climb velocity -#define WPNAV_WP_SPEED_DOWN 150.0f // default maximum descent velocity - -#define WPNAV_WP_ACCEL_Z_DEFAULT 100.0f // default vertical acceleration between waypoints in cm/s/s - class AC_WPNav { public: