Browse Source

Working on comments.

mission-4.1.18
James Goppert 13 years ago
parent
commit
4fa9b7ef85
  1. 9
      libraries/APO/AP_Autopilot.cpp
  2. 6
      libraries/APO/AP_Autopilot.h
  3. 22
      libraries/APO/AP_Navigator.h

9
libraries/APO/AP_Autopilot.cpp

@ -5,14 +5,6 @@ @@ -5,14 +5,6 @@
* Author: jgoppert
*/
/*
* AVR runtime
*/
//#include <avr/io.h>
//#include <avr/eeprom.h>
//#include <avr/pgmspace.h>
//#include <math.h>
#include "../FastSerial/FastSerial.h"
#include "AP_Autopilot.h"
#include "../AP_GPS/AP_GPS.h"
@ -25,7 +17,6 @@ @@ -25,7 +17,6 @@
#include "AP_Guide.h"
#include "AP_BatteryMonitor.h"
namespace apo {
class AP_HardwareAbstractionLayer;

6
libraries/APO/AP_Autopilot.h

@ -113,12 +113,6 @@ private: @@ -113,12 +113,6 @@ private:
AP_Guide * _guide;
AP_Controller * _controller;
AP_HardwareAbstractionLayer * _hal;
/**
* Constants
*/
static const float deg2rad = M_PI / 180;
static const float rad2deg = 180 / M_PI;
};
} // namespace apo

22
libraries/APO/AP_Navigator.h

@ -259,17 +259,17 @@ public: @@ -259,17 +259,17 @@ public:
protected:
AP_HardwareAbstractionLayer * _hal;
private:
int32_t _timeStamp; // micros clock
float _roll; // rad
float _rollRate; //rad/s
float _pitch; // rad
float _pitchRate; // rad/s
float _yaw; // rad
float _yawRate; // rad/s
// wind assumed to be N-E plane
float _windSpeed; // m/s
float _windDirection; // m/s
float _vN;
int32_t _timeStamp; /// time stamp for navigation data, micros clock
float _roll; /// roll angle, radians
float _rollRate; /// roll rate, radians/s
float _pitch; /// pitch angle, radians
float _pitchRate; /// pitch rate, radians/s
float _yaw; /// yaw angle, radians
float _yawRate; /// yaw rate, radians/s
// vertical
float _windSpeed; /// wind speed, m/s
float _windDirection; /// wind directioin, radians
float _vN; ///
float _vE;
float _vD; // m/s
float _xAccel;

Loading…
Cancel
Save