uncrustify libraries/AP_AHRS/AP_AHRS.h

This commit is contained in:
uncrustify 2012-08-21 19:19:51 -07:00 committed by Pat Hickey
parent b4571ca40b
commit b6db467e3c

View File

@ -1,13 +1,13 @@
#ifndef AP_AHRS_H #ifndef AP_AHRS_H
#define AP_AHRS_H #define AP_AHRS_H
/* /*
AHRS (Attitude Heading Reference System) interface for ArduPilot * AHRS (Attitude Heading Reference System) interface for ArduPilot
*
This library is free software; you can redistribute it and/or * This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public * modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either * License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version. * version 2.1 of the License, or (at your option) any later version.
*/ */
#include <AP_Math.h> #include <AP_Math.h>
#include <inttypes.h> #include <inttypes.h>
@ -27,7 +27,7 @@ class AP_AHRS
{ {
public: public:
// Constructor // Constructor
AP_AHRS(IMU *imu, GPS *&gps): AP_AHRS(IMU *imu, GPS *&gps) :
_imu(imu), _imu(imu),
_gps(gps), _gps(gps),
_barometer(NULL) _barometer(NULL)
@ -41,13 +41,22 @@ public:
} }
// empty init // empty init
virtual void init() {}; virtual void init() {
};
// Accessors // Accessors
void set_fly_forward(bool b) { _fly_forward = b; } void set_fly_forward(bool b) {
void set_compass(Compass *compass) { _compass = compass; } _fly_forward = b;
void set_barometer(AP_Baro *barometer) { _barometer = barometer; } }
void set_airspeed(AP_Airspeed *airspeed) { _airspeed = airspeed; } void set_compass(Compass *compass) {
_compass = compass;
}
void set_barometer(AP_Baro *barometer) {
_barometer = barometer;
}
void set_airspeed(AP_Airspeed *airspeed) {
_airspeed = airspeed;
}
// Methods // Methods
virtual void update(void) = 0; virtual void update(void) = 0;