From 65e8b587f94761d0912c7617a85e7c2517b7cbef Mon Sep 17 00:00:00 2001 From: James Goppert Date: Thu, 24 Nov 2011 15:54:08 -0500 Subject: [PATCH] Working on comments. --- libraries/APO/AP_Autopilot.cpp | 9 --------- libraries/APO/AP_Autopilot.h | 6 ------ libraries/APO/AP_Navigator.h | 22 +++++++++++----------- 3 files changed, 11 insertions(+), 26 deletions(-) diff --git a/libraries/APO/AP_Autopilot.cpp b/libraries/APO/AP_Autopilot.cpp index 858695ad3d..4d4847e09a 100644 --- a/libraries/APO/AP_Autopilot.cpp +++ b/libraries/APO/AP_Autopilot.cpp @@ -5,14 +5,6 @@ * Author: jgoppert */ -/* - * AVR runtime - */ -//#include -//#include -//#include -//#include - #include "../FastSerial/FastSerial.h" #include "AP_Autopilot.h" #include "../AP_GPS/AP_GPS.h" @@ -25,7 +17,6 @@ #include "AP_Guide.h" #include "AP_BatteryMonitor.h" - namespace apo { class AP_HardwareAbstractionLayer; diff --git a/libraries/APO/AP_Autopilot.h b/libraries/APO/AP_Autopilot.h index b48737d81b..c508c68d27 100644 --- a/libraries/APO/AP_Autopilot.h +++ b/libraries/APO/AP_Autopilot.h @@ -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 diff --git a/libraries/APO/AP_Navigator.h b/libraries/APO/AP_Navigator.h index 437386c54b..1f71ec8808 100644 --- a/libraries/APO/AP_Navigator.h +++ b/libraries/APO/AP_Navigator.h @@ -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;