mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
New Navigation Lib
git-svn-id: https://arducopter.googlecode.com/svn/trunk@346 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
785162ee8d
commit
e27e8a0e94
libraries/AP_Navigation
@ -1,6 +1,6 @@
|
||||
#include "Navigation.h"
|
||||
|
||||
Navigation::Navigation(AP_GPS *withGPS) :
|
||||
Navigation::Navigation(GPS *withGPS) :
|
||||
_gps(withGPS),
|
||||
_hold_course(-1)
|
||||
{
|
||||
|
@ -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 <AP_GPS.h> // ArduPilot GPS Library
|
||||
#include <GPS.h> // 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
|
||||
|
@ -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
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
|
||||
AP_GPS_IMU gps;
|
||||
Navigation nav((AP_GPS *) & gps);
|
||||
Navigation nav((GPS *) & gps);
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user