mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
uncrustify libraries/AP_AHRS/AP_AHRS.h
This commit is contained in:
parent
8c0e4f3987
commit
af588679b9
@ -1,12 +1,12 @@
|
||||
#ifndef AP_AHRS_H
|
||||
#define AP_AHRS_H
|
||||
/*
|
||||
AHRS (Attitude Heading Reference System) interface for ArduPilot
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
* AHRS (Attitude Heading Reference System) interface for ArduPilot
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*/
|
||||
|
||||
#include <AP_Math.h>
|
||||
@ -41,13 +41,22 @@ public:
|
||||
}
|
||||
|
||||
// empty init
|
||||
virtual void init() {};
|
||||
virtual void init() {
|
||||
};
|
||||
|
||||
// Accessors
|
||||
void set_fly_forward(bool b) { _fly_forward = b; }
|
||||
void set_compass(Compass *compass) { _compass = compass; }
|
||||
void set_barometer(AP_Baro *barometer) { _barometer = barometer; }
|
||||
void set_airspeed(AP_Airspeed *airspeed) { _airspeed = airspeed; }
|
||||
void set_fly_forward(bool b) {
|
||||
_fly_forward = b;
|
||||
}
|
||||
void set_compass(Compass *compass) {
|
||||
_compass = compass;
|
||||
}
|
||||
void set_barometer(AP_Baro *barometer) {
|
||||
_barometer = barometer;
|
||||
}
|
||||
void set_airspeed(AP_Airspeed *airspeed) {
|
||||
_airspeed = airspeed;
|
||||
}
|
||||
|
||||
// Methods
|
||||
virtual void update(void) = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user