mirror of https://github.com/ArduPilot/ardupilot
Working on comments.
This commit is contained in:
parent
d31b1b31f4
commit
65e8b587f9
|
@ -5,14 +5,6 @@
|
||||||
* Author: jgoppert
|
* Author: jgoppert
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/*
|
|
||||||
* AVR runtime
|
|
||||||
*/
|
|
||||||
//#include <avr/io.h>
|
|
||||||
//#include <avr/eeprom.h>
|
|
||||||
//#include <avr/pgmspace.h>
|
|
||||||
//#include <math.h>
|
|
||||||
|
|
||||||
#include "../FastSerial/FastSerial.h"
|
#include "../FastSerial/FastSerial.h"
|
||||||
#include "AP_Autopilot.h"
|
#include "AP_Autopilot.h"
|
||||||
#include "../AP_GPS/AP_GPS.h"
|
#include "../AP_GPS/AP_GPS.h"
|
||||||
|
@ -25,7 +17,6 @@
|
||||||
#include "AP_Guide.h"
|
#include "AP_Guide.h"
|
||||||
#include "AP_BatteryMonitor.h"
|
#include "AP_BatteryMonitor.h"
|
||||||
|
|
||||||
|
|
||||||
namespace apo {
|
namespace apo {
|
||||||
|
|
||||||
class AP_HardwareAbstractionLayer;
|
class AP_HardwareAbstractionLayer;
|
||||||
|
|
|
@ -113,12 +113,6 @@ private:
|
||||||
AP_Guide * _guide;
|
AP_Guide * _guide;
|
||||||
AP_Controller * _controller;
|
AP_Controller * _controller;
|
||||||
AP_HardwareAbstractionLayer * _hal;
|
AP_HardwareAbstractionLayer * _hal;
|
||||||
|
|
||||||
/**
|
|
||||||
* Constants
|
|
||||||
*/
|
|
||||||
static const float deg2rad = M_PI / 180;
|
|
||||||
static const float rad2deg = 180 / M_PI;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace apo
|
} // namespace apo
|
||||||
|
|
|
@ -259,17 +259,17 @@ public:
|
||||||
protected:
|
protected:
|
||||||
AP_HardwareAbstractionLayer * _hal;
|
AP_HardwareAbstractionLayer * _hal;
|
||||||
private:
|
private:
|
||||||
int32_t _timeStamp; // micros clock
|
int32_t _timeStamp; /// time stamp for navigation data, micros clock
|
||||||
float _roll; // rad
|
float _roll; /// roll angle, radians
|
||||||
float _rollRate; //rad/s
|
float _rollRate; /// roll rate, radians/s
|
||||||
float _pitch; // rad
|
float _pitch; /// pitch angle, radians
|
||||||
float _pitchRate; // rad/s
|
float _pitchRate; /// pitch rate, radians/s
|
||||||
float _yaw; // rad
|
float _yaw; /// yaw angle, radians
|
||||||
float _yawRate; // rad/s
|
float _yawRate; /// yaw rate, radians/s
|
||||||
// wind assumed to be N-E plane
|
// vertical
|
||||||
float _windSpeed; // m/s
|
float _windSpeed; /// wind speed, m/s
|
||||||
float _windDirection; // m/s
|
float _windDirection; /// wind directioin, radians
|
||||||
float _vN;
|
float _vN; ///
|
||||||
float _vE;
|
float _vE;
|
||||||
float _vD; // m/s
|
float _vD; // m/s
|
||||||
float _xAccel;
|
float _xAccel;
|
||||||
|
|
Loading…
Reference in New Issue