From e27e8a0e94b8684e6c08715cf7795915e0353a6e Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sun, 29 Aug 2010 22:59:02 +0000 Subject: [PATCH] New Navigation Lib git-svn-id: https://arducopter.googlecode.com/svn/trunk@346 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/AP_Navigation/Navigation.cpp | 2 +- libraries/AP_Navigation/Navigation.h | 6 +++--- libraries/AP_Navigation/examples/Navigation/Navigation.pde | 2 +- .../examples/Navigation_simple/Navigation_simple.pde | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Navigation/Navigation.cpp b/libraries/AP_Navigation/Navigation.cpp index 474a55a273..57849a3138 100644 --- a/libraries/AP_Navigation/Navigation.cpp +++ b/libraries/AP_Navigation/Navigation.cpp @@ -1,6 +1,6 @@ #include "Navigation.h" -Navigation::Navigation(AP_GPS *withGPS) : +Navigation::Navigation(GPS *withGPS) : _gps(withGPS), _hold_course(-1) { diff --git a/libraries/AP_Navigation/Navigation.h b/libraries/AP_Navigation/Navigation.h index 7b3badfbb2..10af920217 100644 --- a/libraries/AP_Navigation/Navigation.h +++ b/libraries/AP_Navigation/Navigation.h @@ -1,6 +1,6 @@ #define XTRACK_GAIN 10 // Amount to compensate for crosstrack (degrees/100 per meter) #define XTRACK_ENTRY_ANGLE 3000 // Max angle used to correct for track following degrees*100 -#include // ArduPilot GPS Library +#include // ArduPilot GPS Library #include "Waypoints.h" // ArduPilot Waypoints Library #include "WProgram.h" @@ -8,7 +8,7 @@ class Navigation { public: - Navigation(AP_GPS *withGPS); + Navigation(GPS *withGPS); void update_gps(void); // called 50 Hz void set_home(Waypoints::WP loc); @@ -37,7 +37,7 @@ private: int32_t wrap_360(int32_t error); // utility int16_t _old_bearing; // used to track delta on the bearing - AP_GPS *_gps; + GPS *_gps; long _crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target float _crosstrack_error; // deg * 100 : 18000 to -18000 meters we are off trackline long _hold_course; // deg * 100 dir of plane diff --git a/libraries/AP_Navigation/examples/Navigation/Navigation.pde b/libraries/AP_Navigation/examples/Navigation/Navigation.pde index dec5adc234..20118cf39e 100644 --- a/libraries/AP_Navigation/examples/Navigation/Navigation.pde +++ b/libraries/AP_Navigation/examples/Navigation/Navigation.pde @@ -11,7 +11,7 @@ This test assumes you are at the LOWl demo Airport AP_GPS_IMU gps; -Navigation nav((AP_GPS *) & gps); +Navigation nav((GPS *) & gps); AP_RC rc; #define CH_ROLL 0 diff --git a/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde b/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde index d8e816a4a2..5c0f21739c 100644 --- a/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde +++ b/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde @@ -4,7 +4,7 @@ AP_GPS_IMU gps; -Navigation nav((AP_GPS *) & gps); +Navigation nav((GPS *) & gps); void setup() {