mirror of https://github.com/ArduPilot/ardupilot
AP_AccelCal: replace header guard with pragma once
This commit is contained in:
parent
3ae4c222e0
commit
155fb6f600
|
@ -1,5 +1,4 @@
|
||||||
#ifndef __AP_ACCELCAL_H__
|
#pragma once
|
||||||
#define __AP_ACCELCAL_H__
|
|
||||||
|
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
#include "AccelCalibrator.h"
|
#include "AccelCalibrator.h"
|
||||||
|
@ -83,5 +82,3 @@ private:
|
||||||
virtual void _acal_event_cancellation() {};
|
virtual void _acal_event_cancellation() {};
|
||||||
virtual void _acal_event_failure() {};
|
virtual void _acal_event_failure() {};
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
|
@ -11,9 +11,8 @@
|
||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
#pragma once
|
||||||
|
|
||||||
#ifndef __ACCELCALIBRATOR_H__
|
|
||||||
#define __ACCELCALIBRATOR_H__
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Math/vectorN.h>
|
#include <AP_Math/vectorN.h>
|
||||||
|
|
||||||
|
@ -144,4 +143,3 @@ private:
|
||||||
void calc_jacob(const Vector3f& sample, const struct param_t& params, VectorP& ret) const;
|
void calc_jacob(const Vector3f& sample, const struct param_t& params, VectorP& ret) const;
|
||||||
void run_fit(uint8_t max_iterations, float& fitness);
|
void run_fit(uint8_t max_iterations, float& fitness);
|
||||||
};
|
};
|
||||||
#endif //__ACCELCALIBRATOR_H__
|
|
||||||
|
|
Loading…
Reference in New Issue