mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_WPNav: move definitions to .cpp file
This commit is contained in:
parent
05ac549155
commit
173de60f25
libraries/AC_WPNav
@ -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
|
||||
|
||||
|
@ -12,18 +12,6 @@
|
||||
#include <AP_Terrain/AP_Terrain.h>
|
||||
#include <AC_Avoidance/AC_Avoid.h> // 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:
|
||||
|
Loading…
Reference in New Issue
Block a user