mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_AHRS/AP_AHRS_MPU6000.cpp
This commit is contained in:
parent
6327305116
commit
9e4e08699d
|
@ -1,14 +1,14 @@
|
|||
/*
|
||||
AP_AHRS_MPU6000.cpp
|
||||
|
||||
AHRS system using MPU6000's internal calculations
|
||||
|
||||
Adapted for the general ArduPilot AHRS interface by Andrew Tridgell
|
||||
|
||||
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.
|
||||
* AP_AHRS_MPU6000.cpp
|
||||
*
|
||||
* AHRS system using MPU6000's internal calculations
|
||||
*
|
||||
* Adapted for the general ArduPilot AHRS interface by Andrew Tridgell
|
||||
*
|
||||
* 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 <FastSerial.h>
|
||||
#include <AP_AHRS.h>
|
||||
|
@ -135,8 +135,8 @@ void AP_AHRS_MPU6000::drift_correction( float deltat )
|
|||
|
||||
|
||||
/*
|
||||
reset the DCM matrix and omega. Used on ground start, and on
|
||||
extreme errors in the matrix
|
||||
* reset the DCM matrix and omega. Used on ground start, and on
|
||||
* extreme errors in the matrix
|
||||
*/
|
||||
void
|
||||
AP_AHRS_MPU6000::reset(bool recover_eulers)
|
||||
|
|
Loading…
Reference in New Issue