Compare commits

...

38 commits

Author SHA1 Message Date
Tyeth Gundry
69fbb4021a
Bump version to 2.4.0 in library.properties 2025-08-26 15:16:15 +01:00
Dan Halbert
7d37a88d79
Merge pull request #43 from dhalbert/clang-fixes
clang format
2025-08-24 18:45:47 -04:00
Dan Halbert
6d80c3abc3 clang format 2025-08-24 18:10:35 -04:00
Dan Halbert
b14657f111
Merge pull request #42 from Every-Flavor-Robotics/master
Fix Gravity Vector Calculation (#35)
2025-08-24 17:40:46 -04:00
Swapnil Pande
1f304b21f1 Fix gravity vector calculation for Mahony filter 2025-08-19 15:13:26 -04:00
Swapnil Pande
b7e1039f9c
Merge branch 'adafruit:master' into master 2025-03-26 11:09:18 -04:00
Tyeth Gundry
8cd362a6ae
Update library.properties - bump version to 2.3.6 2024-03-26 13:07:45 +00:00
Carter Nelson
871109abcd
Merge pull request #39 from caternuson/iss38
Update for LSM6DS3TRC
2024-03-20 13:35:39 -07:00
caternuson
bfe18e94d9 clang 2024-03-20 11:44:51 -07:00
caternuson
bf743c13b1 update for LSM6DS3TRC 2024-03-20 11:27:41 -07:00
Swapnil Pande
3e8f6ca264
Fixed incorrect gravity vector computation 2024-02-25 13:55:05 -05:00
Tyeth Gundry
3b5285f636
Merge pull request #36 from tyeth/bump-version-2023-11-14-20-20-06
Update version number to 2.3.5
2023-11-29 00:51:16 +00:00
tyeth
8d4ebb8526 Warnings 2023-11-29 00:43:18 +00:00
Tyeth Gundry
09ff9f7b07 Bump version number to 2.3.5 2023-11-14 20:20:07 +00:00
dherrada
55a9541375 Update CI action versions 2023-05-12 11:23:56 -04:00
Paint Your Dragon
69b3a854be
Bump version for ESP32 fixed warnings 2022-10-24 17:48:01 -07:00
Paint Your Dragon
007b8b2678
Merge pull request #30 from adafruit/fix-warnings
fix warning emitted by old Adafruit_LSM303_U (archived repo)
2022-10-24 17:36:42 -07:00
hathach
278089246a fix lib depends 2022-10-21 17:47:15 +07:00
hathach
971568365d fix warning emitted by old Adafruit_LSM303_U (archived repo) 2022-10-21 17:32:04 +07:00
Eva Herrada
7d3fbca5ca
Bump to 2.3.2 2022-01-18 17:44:04 -05:00
ToMe25
a55d7baefd
Fix getGravityVector not calculating the actual values (#27)
* Fix getGravityVector not calculating the actual values

* Initializes anglesComputed as false
2022-01-16 13:00:46 -05:00
ToMe25
ef7478b39c
Add gravity vector output to Madgwick and Mahony filter (#26) 2022-01-15 21:15:50 -05:00
Dylan Herrada
c423dcc1b0
Bump to 2.3.1 2021-10-25 15:48:20 -04:00
Patrick Roncagliolo
8da69bad25
Variable delta time, orientation setters (ROS-like) (#16)
* Add orientation setters

This patch enables the user to init the filters with an arbitrary orientation.
This is usually done to place the Z axis aligned with gravity vector.

* Variable time deltas, gains as params

* Fix constructors

* Lint

* Update Adafruit_AHRS_Mahony.h

* Update Adafruit_AHRS_NXPFusion.h

* Update Adafruit_AHRS_FusionInterface.h

* Update Adafruit_AHRS_FusionInterface.h

* Update Adafruit_AHRS_FusionInterface.h
2021-10-23 12:03:30 -04:00
Dylan Herrada
3a8d00bc7b
Bump to 2.3.0 2021-07-22 11:21:56 -04:00
Frédéric Bourgeois
f7534cf5f9
Getter & setter for algorithm parameters (#23)
* Getter & setter for algorithm parameters

Getter and setter for Madgwick (beta) and Mahony (Kp & Ki).

* clang-format
2021-07-17 13:38:34 -04:00
Dylan Herrada
1425f14fbd
Bump to 2.2.4 2021-02-09 16:36:11 -05:00
ToMe25
a6eba1cb7b
Add some doxygen documentation (#19)
* Add some initial NXP docu

gitignore the html folder
I feel like its better to commit the Doxyfile, as i had to add the src
folder as an input for it to generate anything.

* Add Simple AHRS documentation

Slightly improve existing NXP Fusion docu

* Formatting

* Minor Fixes

 * Fix mainpage
 * Document some classes correctly

* Delete Doxyfile
2021-02-09 11:41:23 -05:00
ToMe25
1031b89cf1
Add getters for NXP linear acceleration, gravity vector, and geomagnetic vector (#18)
* Add getters for NXP linear acceleration, gravity vector, and geomagnetic

vector.
Also prevent Adafruit_AHRS_NXPFusion.h from being defined twice.

* Fix Formatting

I don't think i could have known the new line for "in g.", but the other
ones were just me forgetting to format it correctly :)
2021-02-07 13:12:47 -05:00
Dylan Herrada
0083676f40
Bump to 2.0.3 2021-01-05 12:42:57 -05:00
Manoj Nathwani
ca140c7521
better calibration example comments (#15)
* better calibration example comments

see https://github.com/adafruit/Adafruit_AHRS/issues/14

* Update calibration.ino
2020-12-30 18:09:00 -05:00
siddacious
5be5374f73
Update library.properties 2020-04-24 18:17:57 -07:00
siddacious
d41404df31
Update library.properties 2020-04-24 18:16:53 -07:00
siddacious
007b6f9173
Merge pull request #11 from moritzmaier/master
Update Adafruit_AHRS_NXPFusion.cpp resolves #10
2020-04-16 14:52:55 -07:00
Moritz Maier
53cb09aa01
Update Adafruit_AHRS_NXPFusion.cpp 2020-04-14 21:53:54 +02:00
Moritz Maier
28fa8e2e26
Update Adafruit_AHRS_NXPFusion.cpp
This ensures that the first orientation lock is performed, i.e. absolute heading is computed, where yaw = 0 means you head towards magnetic north
2020-04-14 17:00:38 +02:00
siddacious
aa0dab372d
Update library.properties 2020-02-28 17:47:56 -08:00
Ha Thach
7a6947e935
added abstract class Adafruit_AHRS_FusionInterface (#9)
* added abstract class Adafruit_AHRS_FusionInterface

* clang format

* only add virtual to superclass function
2020-02-26 00:19:02 -05:00
22 changed files with 524 additions and 154 deletions

View file

@ -7,11 +7,11 @@ jobs:
runs-on: ubuntu-latest runs-on: ubuntu-latest
steps: steps:
- uses: actions/setup-python@v1 - uses: actions/setup-python@v4
with: with:
python-version: '3.x' python-version: '3.x'
- uses: actions/checkout@v2 - uses: actions/checkout@v3
- uses: actions/checkout@v2 - uses: actions/checkout@v3
with: with:
repository: adafruit/ci-arduino repository: adafruit/ci-arduino
path: ci path: ci

2
.gitignore vendored
View file

@ -1 +1,3 @@
serialconfig.txt serialconfig.txt
.pio
html

View file

@ -2,8 +2,12 @@
Adafruit_LIS3MDL lis3mdl; Adafruit_LIS3MDL lis3mdl;
// Can change this to be LSM6DSOX or whatever ya like // Can change this to be LSM6DSOX or whatever ya like
// For (older) Feather Sense with LSM6DS33, use this:
#include <Adafruit_LSM6DS33.h> #include <Adafruit_LSM6DS33.h>
Adafruit_LSM6DS33 lsm6ds; Adafruit_LSM6DS33 lsm6ds;
// For (newer) Feather Sense with LSM6DS3TR-C, use this:
// #include <Adafruit_LSM6DS3TRC.h>
// Adafruit_LSM6DS3TRC lsm6ds;
bool init_sensors(void) { bool init_sensors(void) {
if (!lsm6ds.begin_I2C() || !lis3mdl.begin_I2C()) { if (!lsm6ds.begin_I2C() || !lis3mdl.begin_I2C()) {

View file

@ -2,7 +2,7 @@
Adafruit_LSM9DS1 lsm9ds = Adafruit_LSM9DS1(); Adafruit_LSM9DS1 lsm9ds = Adafruit_LSM9DS1();
// Or if you have the older LSM9DS0 // Or if you have the older LSM9DS0
//#include <Adafruit_LSM9DS0.h> // #include <Adafruit_LSM9DS0.h>
// Adafruit_LSM9DS0 lsm9ds = Adafruit_LSM9DS0(); // Adafruit_LSM9DS0 lsm9ds = Adafruit_LSM9DS0();
bool init_sensors(void) { bool init_sensors(void) {

View file

@ -13,7 +13,7 @@
Adafruit_Sensor *accelerometer, *gyroscope, *magnetometer; Adafruit_Sensor *accelerometer, *gyroscope, *magnetometer;
// uncomment one combo 9-DoF! // uncomment one combo 9-DoF!
#include "LSM6DS_LIS3MDL.h" // can adjust to LSM6DS33, LSM6DS3U, LSM6DSOX... #include "LSM6DS_LIS3MDL.h" // see the the LSM6DS_LIS3MDL file in this project to change board to LSM6DS33, LSM6DS3U, LSM6DSOX, etc
//#include "LSM9DS.h" // LSM9DS1 or LSM9DS0 //#include "LSM9DS.h" // LSM9DS1 or LSM9DS0
//#include "NXP_FXOS_FXAS.h" // NXP 9-DoF breakout //#include "NXP_FXOS_FXAS.h" // NXP 9-DoF breakout

View file

@ -2,8 +2,12 @@
Adafruit_LIS3MDL lis3mdl; Adafruit_LIS3MDL lis3mdl;
// Can change this to be LSM6DS33 or whatever ya like // Can change this to be LSM6DS33 or whatever ya like
// For (older) Feather Sense with LSM6DS33, use this:
#include <Adafruit_LSM6DS33.h> #include <Adafruit_LSM6DS33.h>
Adafruit_LSM6DS33 lsm6ds; Adafruit_LSM6DS33 lsm6ds;
// For (newer) Feather Sense with LSM6DS3TR-C, use this:
// #include <Adafruit_LSM6DS3TRC.h>
// Adafruit_LSM6DS3TRC lsm6ds;
bool init_sensors(void) { bool init_sensors(void) {
if (!lsm6ds.begin_I2C() || !lis3mdl.begin_I2C()) { if (!lsm6ds.begin_I2C() || !lis3mdl.begin_I2C()) {

View file

@ -1,5 +1,5 @@
//#include <Adafruit_LSM9DS1.h> // #include <Adafruit_LSM9DS1.h>
// Adafruit_LSM9DS1 lsm9ds = Adafruit_LSM9DS1(); // Adafruit_LSM9DS1 lsm9ds = Adafruit_LSM9DS1();
// Or if you have the older LSM9DS0 // Or if you have the older LSM9DS0
#include <Adafruit_LSM9DS0.h> #include <Adafruit_LSM9DS0.h>

View file

@ -15,7 +15,7 @@
Adafruit_Sensor *accelerometer, *gyroscope, *magnetometer; Adafruit_Sensor *accelerometer, *gyroscope, *magnetometer;
// uncomment one combo 9-DoF! // uncomment one combo 9-DoF!
#include "LSM6DS_LIS3MDL.h" // can adjust to LSM6DS33, LSM6DS3U, LSM6DSOX... #include "LSM6DS_LIS3MDL.h" // see the the LSM6DS_LIS3MDL file in this project to change board to LSM6DS33, LSM6DS3U, LSM6DSOX, etc
//#include "LSM9DS.h" // LSM9DS1 or LSM9DS0 //#include "LSM9DS.h" // LSM9DS1 or LSM9DS0
//#include "NXP_FXOS_FXAS.h" // NXP 9-DoF breakout //#include "NXP_FXOS_FXAS.h" // NXP 9-DoF breakout

View file

@ -1,13 +1,14 @@
#include <Wire.h> #include <Wire.h>
#include <Adafruit_Sensor.h> #include <Adafruit_Sensor.h>
#include <Adafruit_LSM303_U.h> #include <Adafruit_LSM303_Accel.h>
#include <Adafruit_LSM303DLH_Mag.h>
#include <Adafruit_BMP085_U.h> #include <Adafruit_BMP085_U.h>
#include <Adafruit_Simple_AHRS.h> #include <Adafruit_Simple_AHRS.h>
// Create sensor instances. // Create sensor instances.
Adafruit_LSM303_Accel_Unified accel(30301); Adafruit_LSM303_Accel_Unified accel(30301);
Adafruit_LSM303_Mag_Unified mag(30302); Adafruit_LSM303DLH_Mag_Unified mag(30302);
Adafruit_BMP085_Unified bmp(18001); Adafruit_BMP085_Unified bmp(18001);
// Create simple AHRS algorithm using the above sensors. // Create simple AHRS algorithm using the above sensors.
Adafruit_Simple_AHRS ahrs(&accel, &mag); Adafruit_Simple_AHRS ahrs(&accel, &mag);

View file

@ -1,11 +1,12 @@
#include <Wire.h> #include <Wire.h>
#include <Adafruit_Sensor.h> #include <Adafruit_Sensor.h>
#include <Adafruit_LSM303_U.h> #include <Adafruit_LSM303_Accel.h>
#include <Adafruit_LSM303DLH_Mag.h>
#include <Adafruit_Simple_AHRS.h> #include <Adafruit_Simple_AHRS.h>
// Create sensor instances. // Create sensor instances.
Adafruit_LSM303_Accel_Unified accel(30301); Adafruit_LSM303_Accel_Unified accel(30301);
Adafruit_LSM303_Mag_Unified mag(30302); Adafruit_LSM303DLH_Mag_Unified mag(30302);
// Create simple AHRS algorithm using the above sensors. // Create simple AHRS algorithm using the above sensors.
Adafruit_Simple_AHRS ahrs(&accel, &mag); Adafruit_Simple_AHRS ahrs(&accel, &mag);

View file

@ -1,5 +1,5 @@
name=Adafruit AHRS name=Adafruit AHRS
version=2.1.0 version=2.4.0
author=Adafruit author=Adafruit
maintainer=Adafruit <info@adafruit.com> maintainer=Adafruit <info@adafruit.com>
sentence=AHRS (Altitude and Heading Reference System) for various Adafruit motion sensors sentence=AHRS (Altitude and Heading Reference System) for various Adafruit motion sensors
@ -7,4 +7,4 @@ paragraph=Includes motion calibration example sketches, as well as calibration o
category=Sensors category=Sensors
url=https://github.com/adafruit/Adafruit_AHRS url=https://github.com/adafruit/Adafruit_AHRS
architectures=* architectures=*
depends=Adafruit Unified Sensor, Adafruit LSM6DS, Adafruit LIS3MDL, Adafruit FXOS8700, Adafruit FXAS21002C, Adafruit LSM9DS1 Library, Adafruit LSM9DS0 Library, Adafruit LSM303DLHC, Adafruit BMP085 Unified, Adafruit BluefruitLE nRF51, SdFat - Adafruit Fork, ArduinoJson, Adafruit SPIFlash, Adafruit Sensor Calibration depends=Adafruit Unified Sensor, Adafruit LSM6DS, Adafruit LIS3MDL, Adafruit FXOS8700, Adafruit FXAS21002C, Adafruit LSM9DS1 Library, Adafruit LSM9DS0 Library, Adafruit BMP085 Unified, Adafruit BluefruitLE nRF51, SdFat - Adafruit Fork, ArduinoJson, Adafruit SPIFlash, Adafruit Sensor Calibration, Adafruit LSM303 Accel, Adafruit LSM303DLH Mag

View file

@ -1,3 +1,26 @@
/*!
* @file Adafruit_AHRS
*
* @mainpage Adafruit AHRS
*
* @section intro_sec Introduction
*
* This library lets you take an accelerometer, gyroscope and magnetometer
* and combine the data to create orientation data.
*
* Options are Mahony (lowest memory/computation),
* Madgwick (fair memory/computation), and NXP fusion/Kalman (highest).
*
* While in theory these can run on an Arduino UNO/Atmega328P we really
* recommend a SAMD21 or better. Having single-instruction floating point
* multiply and plenty of RAM will help a lot!
*/
#ifndef __ADAFRUIT_AHRS_H_
#define __ADAFRUIT_AHRS_H_
#include <Adafruit_AHRS_Madgwick.h> #include <Adafruit_AHRS_Madgwick.h>
#include <Adafruit_AHRS_Mahony.h> #include <Adafruit_AHRS_Mahony.h>
#include <Adafruit_AHRS_NXPFusion.h> #include <Adafruit_AHRS_NXPFusion.h>
#endif // __ADAFRUIT_AHRS_H_

View file

@ -0,0 +1,105 @@
/*!
* @file Adafruit_AHRS_FusionInterface.h
*
* @section license License
*
* The MIT License (MIT)
*
* Copyright (c) 2020 Ha Thach (tinyusb.org) for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef ADAFRUIT_AHRS_FUSIONINTERFACE_H_
#define ADAFRUIT_AHRS_FUSIONINTERFACE_H_
/*!
* @brief The common interface for the fusion algorithms.
*/
class Adafruit_AHRS_FusionInterface {
public:
/**************************************************************************/
/*!
* @brief Initializes the sensor fusion filter.
*
* @param sampleFrequency The sensor sample rate in herz(samples per second).
*/
/**************************************************************************/
virtual void begin(float sampleFrequency) = 0;
/**************************************************************************/
/*!
* @brief Updates the filter with new gyroscope, accelerometer, and
* magnetometer data.
*
* @param gx The gyroscope x axis. In DPS.
* @param gy The gyroscope y axis. In DPS.
* @param gz The gyroscope z axis. In DPS.
* @param ax The accelerometer x axis. In g.
* @param ay The accelerometer y axis. In g.
* @param az The accelerometer z axis. In g.
* @param mx The magnetometer x axis. In uT.
* @param my The magnetometer y axis. In uT.
* @param mz The magnetometer z axis. In uT.
*/
/**************************************************************************/
virtual void update(float gx, float gy, float gz, float ax, float ay,
float az, float mx, float my, float mz) = 0;
/**************************************************************************/
/*!
* @brief Gets the current roll of the sensors.
*
* @return The current sensor roll.
*/
/**************************************************************************/
virtual float getRoll() = 0;
/**************************************************************************/
/*!
* @brief Gets the current pitch of the sensors.
*
* @return The current sensor pitch.
*/
/**************************************************************************/
virtual float getPitch() = 0;
/**************************************************************************/
/*!
* @brief Gets the current yaw of the sensors.
*
* @return The current sensor yaw.
*/
/**************************************************************************/
virtual float getYaw() = 0;
virtual void getQuaternion(float *w, float *x, float *y, float *z) = 0;
virtual void setQuaternion(float w, float x, float y, float z) = 0;
/**************************************************************************/
/*!
* @brief Gets the current gravity vector of the sensor.
*
* @param x A float pointer to write the gravity vector x component to. In g.
* @param y A float pointer to write the gravity vector y component to. In g.
* @param z A float pointer to write the gravity vector z component to. In g.
*/
virtual void getGravityVector(float *x, float *y, float *z) = 0;
};
#endif /* ADAFRUIT_AHRS_FUSIONINTERFACE_H_ */

View file

@ -34,18 +34,21 @@
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------
// AHRS algorithm update // AHRS algorithm update
Adafruit_Madgwick::Adafruit_Madgwick() { Adafruit_Madgwick::Adafruit_Madgwick() : Adafruit_Madgwick(betaDef) {}
beta = betaDef;
Adafruit_Madgwick::Adafruit_Madgwick(float gain) {
beta = gain;
q0 = 1.0f; q0 = 1.0f;
q1 = 0.0f; q1 = 0.0f;
q2 = 0.0f; q2 = 0.0f;
q3 = 0.0f; q3 = 0.0f;
invSampleFreq = 1.0f / sampleFreqDef; invSampleFreq = 1.0f / sampleFreqDef;
anglesComputed = 0; anglesComputed = false;
} }
void Adafruit_Madgwick::update(float gx, float gy, float gz, float ax, float ay, void Adafruit_Madgwick::update(float gx, float gy, float gz, float ax, float ay,
float az, float mx, float my, float mz) { float az, float mx, float my, float mz,
float dt) {
float recipNorm; float recipNorm;
float s0, s1, s2, s3; float s0, s1, s2, s3;
float qDot1, qDot2, qDot3, qDot4; float qDot1, qDot2, qDot3, qDot4;
@ -57,7 +60,7 @@ void Adafruit_Madgwick::update(float gx, float gy, float gz, float ax, float ay,
// Use IMU algorithm if magnetometer measurement invalid (avoids NaN in // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in
// magnetometer normalisation) // magnetometer normalisation)
if ((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { if ((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
updateIMU(gx, gy, gz, ax, ay, az); updateIMU(gx, gy, gz, ax, ay, az, dt);
return; return;
} }
@ -167,10 +170,10 @@ void Adafruit_Madgwick::update(float gx, float gy, float gz, float ax, float ay,
} }
// Integrate rate of change of quaternion to yield quaternion // Integrate rate of change of quaternion to yield quaternion
q0 += qDot1 * invSampleFreq; q0 += qDot1 * dt;
q1 += qDot2 * invSampleFreq; q1 += qDot2 * dt;
q2 += qDot3 * invSampleFreq; q2 += qDot3 * dt;
q3 += qDot4 * invSampleFreq; q3 += qDot4 * dt;
// Normalise quaternion // Normalise quaternion
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
@ -185,7 +188,7 @@ void Adafruit_Madgwick::update(float gx, float gy, float gz, float ax, float ay,
// IMU algorithm update // IMU algorithm update
void Adafruit_Madgwick::updateIMU(float gx, float gy, float gz, float ax, void Adafruit_Madgwick::updateIMU(float gx, float gy, float gz, float ax,
float ay, float az) { float ay, float az, float dt) {
float recipNorm; float recipNorm;
float s0, s1, s2, s3; float s0, s1, s2, s3;
float qDot1, qDot2, qDot3, qDot4; float qDot1, qDot2, qDot3, qDot4;
@ -250,10 +253,10 @@ void Adafruit_Madgwick::updateIMU(float gx, float gy, float gz, float ax,
} }
// Integrate rate of change of quaternion to yield quaternion // Integrate rate of change of quaternion to yield quaternion
q0 += qDot1 * invSampleFreq; q0 += qDot1 * dt;
q1 += qDot2 * invSampleFreq; q1 += qDot2 * dt;
q2 += qDot3 * invSampleFreq; q2 += qDot3 * dt;
q3 += qDot4 * invSampleFreq; q3 += qDot4 * dt;
// Normalise quaternion // Normalise quaternion
recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
@ -264,19 +267,29 @@ void Adafruit_Madgwick::updateIMU(float gx, float gy, float gz, float ax,
anglesComputed = 0; anglesComputed = 0;
} }
void Adafruit_Madgwick::update(float gx, float gy, float gz, float ax, float ay,
float az, float mx, float my, float mz) {
update(gx, gy, gz, ax, ay, az, mx, my, mz, invSampleFreq);
}
void Adafruit_Madgwick::updateIMU(float gx, float gy, float gz, float ax,
float ay, float az) {
updateIMU(gx, gy, gz, ax, ay, az, invSampleFreq);
};
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------
// Fast inverse square-root // Fast inverse square-root
// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root // See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
float Adafruit_Madgwick::invSqrt(float x) { float Adafruit_Madgwick::invSqrt(float x) {
float halfx = 0.5f * x; float halfx = 0.5f * x;
float y = x; union {
long i = *(long *)&y; float f;
i = 0x5f3759df - (i >> 1); long i;
y = *(float *)&i; } conv = {x};
y = y * (1.5f - (halfx * y * y)); conv.i = 0x5f3759df - (conv.i >> 1);
y = y * (1.5f - (halfx * y * y)); conv.f *= 1.5f - (halfx * conv.f * conv.f);
return y; conv.f *= 1.5f - (halfx * conv.f * conv.f);
return conv.f;
} }
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------
@ -285,5 +298,8 @@ void Adafruit_Madgwick::computeAngles() {
roll = atan2f(q0 * q1 + q2 * q3, 0.5f - q1 * q1 - q2 * q2); roll = atan2f(q0 * q1 + q2 * q3, 0.5f - q1 * q1 - q2 * q2);
pitch = asinf(-2.0f * (q1 * q3 - q0 * q2)); pitch = asinf(-2.0f * (q1 * q3 - q0 * q2));
yaw = atan2f(q1 * q2 + q0 * q3, 0.5f - q2 * q2 - q3 * q3); yaw = atan2f(q1 * q2 + q0 * q3, 0.5f - q2 * q2 - q3 * q3);
grav[0] = 2.0f * (q1 * q3 - q0 * q2);
grav[1] = 2.0f * (q0 * q1 + q2 * q3);
grav[2] = 2.0f * (q0 * q0 - 0.5f + q3 * q3);
anglesComputed = 1; anglesComputed = 1;
} }

View file

@ -16,11 +16,13 @@
//============================================================================================= //=============================================================================================
#ifndef __Adafruit_Madgwick_h__ #ifndef __Adafruit_Madgwick_h__
#define __Adafruit_Madgwick_h__ #define __Adafruit_Madgwick_h__
#include "Adafruit_AHRS_FusionInterface.h"
#include <math.h> #include <math.h>
//-------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------
// Variable declaration // Variable declaration
class Adafruit_Madgwick { class Adafruit_Madgwick : public Adafruit_AHRS_FusionInterface {
private: private:
static float invSqrt(float x); static float invSqrt(float x);
float beta; // algorithm gain float beta; // algorithm gain
@ -29,24 +31,30 @@ private:
float q2; float q2;
float q3; // quaternion of sensor frame relative to auxiliary frame float q3; // quaternion of sensor frame relative to auxiliary frame
float invSampleFreq; float invSampleFreq;
float roll; float roll, pitch, yaw;
float pitch; float grav[3];
float yaw; bool anglesComputed = false;
char anglesComputed;
void computeAngles(); void computeAngles();
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------
// Function declarations // Function declarations
public: public:
Adafruit_Madgwick(void); Adafruit_Madgwick();
Adafruit_Madgwick(float gain);
void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; } void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; }
void update(float gx, float gy, float gz, float ax, float ay, float az, void update(float gx, float gy, float gz, float ax, float ay, float az,
float mx, float my, float mz); float mx, float my, float mz);
void updateIMU(float gx, float gy, float gz, float ax, float ay, float az); void updateIMU(float gx, float gy, float gz, float ax, float ay, float az);
void update(float gx, float gy, float gz, float ax, float ay, float az,
float mx, float my, float mz, float dt);
void updateIMU(float gx, float gy, float gz, float ax, float ay, float az,
float dt);
// float getPitch(){return atan2f(2.0f * q2 * q3 - 2.0f * q0 * q1, 2.0f * q0 * // float getPitch(){return atan2f(2.0f * q2 * q3 - 2.0f * q0 * q1, 2.0f * q0 *
// q0 + 2.0f * q3 * q3 - 1.0f);}; float getRoll(){return -1.0f * asinf(2.0f * // q0 + 2.0f * q3 * q3 - 1.0f);}; float getRoll(){return -1.0f * asinf(2.0f *
// q1 * q3 + 2.0f * q0 * q2);}; float getYaw(){return atan2f(2.0f * q1 * q2 // q1 * q3 + 2.0f * q0 * q2);}; float getYaw(){return atan2f(2.0f * q1 * q2
// - 2.0f * q0 * q3, 2.0f * q0 * q0 + 2.0f * q1 * q1 - 1.0f);}; // - 2.0f * q0 * q3, 2.0f * q0 * q0 + 2.0f * q1 * q1 - 1.0f);};
float getBeta() { return beta; }
void setBeta(float beta) { this->beta = beta; }
float getRoll() { float getRoll() {
if (!anglesComputed) if (!anglesComputed)
computeAngles(); computeAngles();
@ -83,5 +91,18 @@ public:
*y = q2; *y = q2;
*z = q3; *z = q3;
} }
void setQuaternion(float w, float x, float y, float z) {
q0 = w;
q1 = x;
q2 = y;
q3 = z;
}
void getGravityVector(float *x, float *y, float *z) {
if (!anglesComputed)
computeAngles();
*x = grav[0];
*y = grav[1];
*z = grav[2];
}
}; };
#endif #endif

View file

@ -37,9 +37,11 @@
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------
// AHRS algorithm update // AHRS algorithm update
Adafruit_Mahony::Adafruit_Mahony() { Adafruit_Mahony::Adafruit_Mahony() : Adafruit_Mahony(twoKpDef, twoKiDef) {}
twoKp = twoKpDef; // 2 * proportional gain (Kp)
twoKi = twoKiDef; // 2 * integral gain (Ki) Adafruit_Mahony::Adafruit_Mahony(float prop_gain, float int_gain) {
twoKp = prop_gain; // 2 * proportional gain (Kp)
twoKi = int_gain; // 2 * integral gain (Ki)
q0 = 1.0f; q0 = 1.0f;
q1 = 0.0f; q1 = 0.0f;
q2 = 0.0f; q2 = 0.0f;
@ -47,12 +49,12 @@ Adafruit_Mahony::Adafruit_Mahony() {
integralFBx = 0.0f; integralFBx = 0.0f;
integralFBy = 0.0f; integralFBy = 0.0f;
integralFBz = 0.0f; integralFBz = 0.0f;
anglesComputed = 0; anglesComputed = false;
invSampleFreq = 1.0f / DEFAULT_SAMPLE_FREQ; invSampleFreq = 1.0f / DEFAULT_SAMPLE_FREQ;
} }
void Adafruit_Mahony::update(float gx, float gy, float gz, float ax, float ay, void Adafruit_Mahony::update(float gx, float gy, float gz, float ax, float ay,
float az, float mx, float my, float mz) { float az, float mx, float my, float mz, float dt) {
float recipNorm; float recipNorm;
float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; float q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3;
float hx, hy, bx, bz; float hx, hy, bx, bz;
@ -126,9 +128,9 @@ void Adafruit_Mahony::update(float gx, float gy, float gz, float ax, float ay,
// Compute and apply integral feedback if enabled // Compute and apply integral feedback if enabled
if (twoKi > 0.0f) { if (twoKi > 0.0f) {
// integral error scaled by Ki // integral error scaled by Ki
integralFBx += twoKi * halfex * invSampleFreq; integralFBx += twoKi * halfex * dt;
integralFBy += twoKi * halfey * invSampleFreq; integralFBy += twoKi * halfey * dt;
integralFBz += twoKi * halfez * invSampleFreq; integralFBz += twoKi * halfez * dt;
gx += integralFBx; // apply integral feedback gx += integralFBx; // apply integral feedback
gy += integralFBy; gy += integralFBy;
gz += integralFBz; gz += integralFBz;
@ -145,9 +147,9 @@ void Adafruit_Mahony::update(float gx, float gy, float gz, float ax, float ay,
} }
// Integrate rate of change of quaternion // Integrate rate of change of quaternion
gx *= (0.5f * invSampleFreq); // pre-multiply common factors gx *= (0.5f * dt); // pre-multiply common factors
gy *= (0.5f * invSampleFreq); gy *= (0.5f * dt);
gz *= (0.5f * invSampleFreq); gz *= (0.5f * dt);
qa = q0; qa = q0;
qb = q1; qb = q1;
qc = q2; qc = q2;
@ -169,7 +171,7 @@ void Adafruit_Mahony::update(float gx, float gy, float gz, float ax, float ay,
// IMU algorithm update // IMU algorithm update
void Adafruit_Mahony::updateIMU(float gx, float gy, float gz, float ax, void Adafruit_Mahony::updateIMU(float gx, float gy, float gz, float ax,
float ay, float az) { float ay, float az, float dt) {
float recipNorm; float recipNorm;
float halfvx, halfvy, halfvz; float halfvx, halfvy, halfvz;
float halfex, halfey, halfez; float halfex, halfey, halfez;
@ -204,9 +206,9 @@ void Adafruit_Mahony::updateIMU(float gx, float gy, float gz, float ax,
// Compute and apply integral feedback if enabled // Compute and apply integral feedback if enabled
if (twoKi > 0.0f) { if (twoKi > 0.0f) {
// integral error scaled by Ki // integral error scaled by Ki
integralFBx += twoKi * halfex * invSampleFreq; integralFBx += twoKi * halfex * dt;
integralFBy += twoKi * halfey * invSampleFreq; integralFBy += twoKi * halfey * dt;
integralFBz += twoKi * halfez * invSampleFreq; integralFBz += twoKi * halfez * dt;
gx += integralFBx; // apply integral feedback gx += integralFBx; // apply integral feedback
gy += integralFBy; gy += integralFBy;
gz += integralFBz; gz += integralFBz;
@ -223,9 +225,9 @@ void Adafruit_Mahony::updateIMU(float gx, float gy, float gz, float ax,
} }
// Integrate rate of change of quaternion // Integrate rate of change of quaternion
gx *= (0.5f * invSampleFreq); // pre-multiply common factors gx *= (0.5f * dt); // pre-multiply common factors
gy *= (0.5f * invSampleFreq); gy *= (0.5f * dt);
gz *= (0.5f * invSampleFreq); gz *= (0.5f * dt);
qa = q0; qa = q0;
qb = q1; qb = q1;
qc = q2; qc = q2;
@ -243,19 +245,30 @@ void Adafruit_Mahony::updateIMU(float gx, float gy, float gz, float ax,
anglesComputed = 0; anglesComputed = 0;
} }
void Adafruit_Mahony::update(float gx, float gy, float gz, float ax, float ay,
float az, float mx, float my, float mz) {
update(gx, gy, gz, ax, ay, az, mx, my, mz, invSampleFreq);
}
void Adafruit_Mahony::updateIMU(float gx, float gy, float gz, float ax,
float ay, float az) {
updateIMU(gx, gy, gz, ax, ay, az, invSampleFreq);
};
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------
// Fast inverse square-root // Fast inverse square-root
// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root // See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
float Adafruit_Mahony::invSqrt(float x) { float Adafruit_Mahony::invSqrt(float x) {
float halfx = 0.5f * x; float halfx = 0.5f * x;
float y = x; union {
long i = *(long *)&y; float f;
i = 0x5f3759df - (i >> 1); long i;
y = *(float *)&i; } conv = {x};
y = y * (1.5f - (halfx * y * y)); conv.i = 0x5f3759df - (conv.i >> 1);
y = y * (1.5f - (halfx * y * y)); conv.f *= 1.5f - (halfx * conv.f * conv.f);
return y; conv.f *= 1.5f - (halfx * conv.f * conv.f);
return conv.f;
} }
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------
@ -264,6 +277,9 @@ void Adafruit_Mahony::computeAngles() {
roll = atan2f(q0 * q1 + q2 * q3, 0.5f - q1 * q1 - q2 * q2); roll = atan2f(q0 * q1 + q2 * q3, 0.5f - q1 * q1 - q2 * q2);
pitch = asinf(-2.0f * (q1 * q3 - q0 * q2)); pitch = asinf(-2.0f * (q1 * q3 - q0 * q2));
yaw = atan2f(q1 * q2 + q0 * q3, 0.5f - q2 * q2 - q3 * q3); yaw = atan2f(q1 * q2 + q0 * q3, 0.5f - q2 * q2 - q3 * q3);
grav[0] = 2.0f * (q1 * q3 - q0 * q2);
grav[1] = 2.0f * (q0 * q1 + q2 * q3);
grav[2] = 2.0f * (q0 * q0 - 0.5f + q3 * q3);
anglesComputed = 1; anglesComputed = 1;
} }

View file

@ -12,12 +12,14 @@
//============================================================================================= //=============================================================================================
#ifndef __Adafruit_Mahony_h__ #ifndef __Adafruit_Mahony_h__
#define __Adafruit_Mahony_h__ #define __Adafruit_Mahony_h__
#include "Adafruit_AHRS_FusionInterface.h"
#include <math.h> #include <math.h>
//-------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------
// Variable declaration // Variable declaration
class Adafruit_Mahony { class Adafruit_Mahony : public Adafruit_AHRS_FusionInterface {
private: private:
float twoKp; // 2 * proportional gain (Kp) float twoKp; // 2 * proportional gain (Kp)
float twoKi; // 2 * integral gain (Ki) float twoKi; // 2 * integral gain (Ki)
@ -27,7 +29,8 @@ private:
integralFBz; // integral error terms scaled by Ki integralFBz; // integral error terms scaled by Ki
float invSampleFreq; float invSampleFreq;
float roll, pitch, yaw; float roll, pitch, yaw;
char anglesComputed; float grav[3];
bool anglesComputed = false;
static float invSqrt(float x); static float invSqrt(float x);
void computeAngles(); void computeAngles();
@ -36,10 +39,19 @@ private:
public: public:
Adafruit_Mahony(); Adafruit_Mahony();
Adafruit_Mahony(float prop_gain, float int_gain);
void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; } void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; }
void update(float gx, float gy, float gz, float ax, float ay, float az, void update(float gx, float gy, float gz, float ax, float ay, float az,
float mx, float my, float mz); float mx, float my, float mz);
void updateIMU(float gx, float gy, float gz, float ax, float ay, float az); void updateIMU(float gx, float gy, float gz, float ax, float ay, float az);
void update(float gx, float gy, float gz, float ax, float ay, float az,
float mx, float my, float mz, float dt);
void updateIMU(float gx, float gy, float gz, float ax, float ay, float az,
float dt);
float getKp() { return twoKp / 2.0f; }
void setKp(float Kp) { twoKp = 2.0f * Kp; }
float getKi() { return twoKi / 2.0f; }
void setKi(float Ki) { twoKi = 2.0f * Ki; }
float getRoll() { float getRoll() {
if (!anglesComputed) if (!anglesComputed)
computeAngles(); computeAngles();
@ -76,6 +88,19 @@ public:
*y = q2; *y = q2;
*z = q3; *z = q3;
} }
void setQuaternion(float w, float x, float y, float z) {
q0 = w;
q1 = x;
q2 = y;
q3 = z;
}
void getGravityVector(float *x, float *y, float *z) {
if (!anglesComputed)
computeAngles();
*x = grav[0];
*y = grav[1];
*z = grav[2];
}
}; };
#endif #endif

View file

@ -1,34 +1,39 @@
// Copyright (c) 2014, Freescale Semiconductor, Inc. /*!
// All rights reserved. * @file Adafruit_AHRS_NXPFusion.cpp
// vim: set ts=4: *
// * @section license License
// Redistribution and use in source and binary forms, with or without *
// modification, are permitted provided that the following conditions are met: * Copyright (c) 2014, Freescale Semiconductor, Inc.
// * Redistributions of source code must retain the above copyright * All rights reserved.
// notice, this list of conditions and the following disclaimer. * vim: set ts=4:
// * Redistributions in binary form must reproduce the above copyright *
// notice, this list of conditions and the following disclaimer in the * Redistribution and use in source and binary forms, with or without
// documentation and/or other materials provided with the distribution. * modification, are permitted provided that the following conditions are met:
// * Neither the name of Freescale Semiconductor, Inc. nor the * * Redistributions of source code must retain the above copyright
// names of its contributors may be used to endorse or promote products * notice, this list of conditions and the following disclaimer.
// derived from this software without specific prior written permission. * * Redistributions in binary form must reproduce the above copyright
// * notice, this list of conditions and the following disclaimer in the
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * documentation and/or other materials provided with the distribution.
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * * Neither the name of Freescale Semiconductor, Inc. nor the
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * names of its contributors may be used to endorse or promote products
// ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR * derived from this software without specific prior written permission.
// ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL *
// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE * ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
// * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
// This is the file that contains the fusion routines. It is STRONGLY * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// RECOMMENDED that the casual developer NOT TOUCH THIS FILE. The mathematics * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
// behind this file is extremely complex, and it will be very easy (almost * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// inevitable) that you screw it up. * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
// *
* This is the file that contains the fusion routines. It is STRONGLY
* RECOMMENDED that the casual developer NOT TOUCH THIS FILE. The mathematics
* behind this file is extremely complex, and it will be very easy (almost
* inevitable) that you screw it up.
*/
#include "Adafruit_AHRS_NXPFusion.h" #include "Adafruit_AHRS_NXPFusion.h"
@ -111,8 +116,12 @@ void fmatrixAeqInvA(float *A[], int8_t iColInd[], int8_t iRowInd[],
void fmatrixAeqRenormRotA(float A[][3]); void fmatrixAeqRenormRotA(float A[][3]);
} }
// initialize the 9DOF Kalman filter /**************************************************************************/
void Adafruit_NXPSensorFusion::begin(float sampleRate) { /*!
* @brief Initializes the 9DOF Kalman filter.
*/
/**************************************************************************/
void Adafruit_NXPSensorFusion::begin(float sampleFrequency) {
int8_t i, j; int8_t i, j;
// reset the flag denoting that a first 9DOF orientation lock has been // reset the flag denoting that a first 9DOF orientation lock has been
@ -121,7 +130,7 @@ void Adafruit_NXPSensorFusion::begin(float sampleRate) {
// compute and store useful product terms to save floating point calculations // compute and store useful product terms to save floating point calculations
// later // later
Fastdeltat = 1.0f / sampleRate; Fastdeltat = 1.0f / sampleFrequency;
deltat = Fastdeltat; deltat = Fastdeltat;
deltatsq = deltat * deltat; deltatsq = deltat * deltat;
casq = FCA_9DOF_GBY_KALMAN * FCA_9DOF_GBY_KALMAN; casq = FCA_9DOF_GBY_KALMAN * FCA_9DOF_GBY_KALMAN;
@ -186,11 +195,12 @@ void Adafruit_NXPSensorFusion::begin(float sampleRate) {
resetflag = 0; resetflag = 0;
} }
// 9DOF orientation function implemented using a 12 element Kalman filter /**************************************************************************/
// void fRun_9DOF_GBY_KALMAN(SV_9DOF_GBY_KALMAN_t *SV, /*!
// const AccelSensor_t *Accel, const MagSensor_t *Mag, const GyroSensor_t *Gyro, * @brief Updates the filter with new gyroscope, accelerometer, and magnetometer
// const MagCalibration_t *MagCal) * data.
*/
/**************************************************************************/
void Adafruit_NXPSensorFusion::update(float gx, float gy, float gz, float ax, void Adafruit_NXPSensorFusion::update(float gx, float gy, float gz, float ax,
float ay, float az, float mx, float my, float ay, float az, float mx, float my,
float mz) { float mz) {
@ -238,7 +248,7 @@ void Adafruit_NXPSensorFusion::update(float gx, float gy, float gz, float ax,
// initial orientation lock to accelerometer and magnetometer eCompass // initial orientation lock to accelerometer and magnetometer eCompass
// orientation // orientation
// ********************************************************************************* // *********************************************************************************
if (fabsf(mx) >= 20.0f && fabsf(mx) >= 20.0f && fabsf(mx) >= 20.0f) { if (fabsf(mx) <= 50.0f && fabsf(my) <= 50.0f && fabsf(mz) <= 50.0f) {
ValidMagCal = 1; ValidMagCal = 1;
} else { } else {
ValidMagCal = 0; ValidMagCal = 0;
@ -302,7 +312,7 @@ void Adafruit_NXPSensorFusion::update(float gx, float gy, float gz, float ax,
// (with magnitude 1g) NED gravity is along positive z axis // (with magnitude 1g) NED gravity is along positive z axis
gSeGyMi[i] = RMi[i][Z]; gSeGyMi[i] = RMi[i][Z];
// compute a priori acceleration (a-) (g, sensor frame) from decayed a // compute the a priori acceleration (a-) (g, sensor frame) from decayed a
// posteriori estimate (g, sensor frame) // posteriori estimate (g, sensor frame)
aSeMi[i] = FCA_9DOF_GBY_KALMAN * aSePl[i]; aSeMi[i] = FCA_9DOF_GBY_KALMAN * aSePl[i];
@ -623,7 +633,7 @@ void Adafruit_NXPSensorFusion::update(float gx, float gy, float gz, float ax,
mGl[X] = DEFAULTB * fcosdelta; // TODO: MagCal->B mGl[X] = DEFAULTB * fcosdelta; // TODO: MagCal->B
mGl[Z] = DEFAULTB * fsindelta; mGl[Z] = DEFAULTB * fsindelta;
} // end hyp == 0.0F } // end hyp == 0.0F
} // end ValidMagCal } // end ValidMagCal
// ********************************************************************************* // *********************************************************************************
// compute the a posteriori Euler angles from the orientation matrix // compute the a posteriori Euler angles from the orientation matrix

View file

@ -1,39 +1,81 @@
/*!
* @file Adafruit_AHRS_NXPFusion.h
*
* @section license License
*
* This is a modification of
* https://github.com/memsindustrygroup/Open-Source-Sensor-Fusion/blob/master/Sources/tasks.h
* by PJRC / Paul Stoffregen https://github.com/PaulStoffregen/NXPMotionSense
*
* Copyright (c) 2014, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of Freescale Semiconductor, Inc. nor the
* names of its contributors may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __Adafruit_Nxp_Fusion_h_
#define __Adafruit_Nxp_Fusion_h_
#include "Adafruit_AHRS_FusionInterface.h"
#include <Arduino.h> #include <Arduino.h>
// This is a modification of /*!
// https://github.com/memsindustrygroup/Open-Source-Sensor-Fusion/blob/master/Sources/tasks.h * @brief Kalman/NXP Fusion algorithm.
// by PJRC / Paul Stoffregen https://github.com/PaulStoffregen/NXPMotionSense */
class Adafruit_NXPSensorFusion : public Adafruit_AHRS_FusionInterface {
// Copyright (c) 2014, Freescale Semiconductor, Inc.
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of Freescale Semiconductor, Inc. nor the
// names of its contributors may be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR
// ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// changed class name to avoid collision
class Adafruit_NXPSensorFusion {
public: public:
void begin(float sampleRate = 100.0f); /**************************************************************************/
/*!
* @brief Initializes the 9DOF Kalman filter.
*
* @param sampleFrequency The sensor sample rate in herz(samples per second).
*/
/**************************************************************************/
void begin(float sampleFrequency = 100.0f);
/**************************************************************************/
/*!
* @brief Updates the filter with new gyroscope, accelerometer, and
* magnetometer data. For roll, pitch, and yaw the accelerometer values can be
* either m/s^2 or g, but for linear acceleration they have to be in g.
*
* 9DOF orientation function implemented using a 12 element Kalman filter
*
* void fRun_9DOF_GBY_KALMAN(SV_9DOF_GBY_KALMAN_t *SV,
* const AccelSensor_t *Accel, const MagSensor_t *Mag,
* const GyroSensor_t *Gyro, const MagCalibration_t *MagCal)
*
* @param gx The gyroscope x axis. In DPS.
* @param gy The gyroscope y axis. In DPS.
* @param gz The gyroscope z axis. In DPS.
* @param ax The accelerometer x axis. In g.
* @param ay The accelerometer y axis. In g.
* @param az The accelerometer z axis. In g.
* @param mx The magnetometer x axis. In uT.
* @param my The magnetometer y axis. In uT.
* @param mz The magnetometer z axis. In uT.
*/
/**************************************************************************/
void update(float gx, float gy, float gz, float ax, float ay, float az, void update(float gx, float gy, float gz, float ax, float ay, float az,
float mx, float my, float mz); float mx, float my, float mz);
@ -48,6 +90,58 @@ public:
*z = qPl.q3; *z = qPl.q3;
} }
void setQuaternion(float w, float x, float y, float z) {
qPl.q0 = w;
qPl.q1 = x;
qPl.q2 = y;
qPl.q3 = z;
}
/**************************************************************************/
/*!
* @brief Get the linear acceleration part of the acceleration value given to
* update.
*
* @param x The pointer to write the linear acceleration x axis to. In g.
* @param y The pointer to write the linear acceleration y axis to. In g.
* @param z The pointer to write the linear acceleration z axis to. In g.
*/
/**************************************************************************/
void getLinearAcceleration(float *x, float *y, float *z) const {
*x = aSePl[0];
*y = aSePl[1];
*z = aSePl[2];
}
/**************************************************************************/
/*!
* @brief Get the gravity vector from the gyroscope values.
*
* @param x A float pointer to write the gravity vector x component to. In g.
* @param y A float pointer to write the gravity vector y component to. In g.
* @param z A float pointer to write the gravity vector z component to. In g.
*/
/**************************************************************************/
void getGravityVector(float *x, float *y, float *z) {
*x = gSeGyMi[0];
*y = gSeGyMi[1];
*z = gSeGyMi[2];
}
/**************************************************************************/
/*!
* @brief Get the geomagnetic vector in global frame.
*
* @param x The pointer to write the geomagnetic vector x axis to. In uT.
* @param y The pointer to write the geomagnetic vector y axis to. In uT.
* @param z The pointer to write the geomagnetic vector z axis to. In uT.
*/
/**************************************************************************/
void getGeomagneticVector(float *x, float *y, float *z) const {
*x = mGl[0];
*y = mGl[1];
*z = mGl[2];
}
typedef struct { typedef struct {
float q0; // w float q0; // w
float q1; // x float q1; // x
@ -119,3 +213,5 @@ private:
FirstOrientationLock; // denotes that 9DOF orientation has locked to 6DOF FirstOrientationLock; // denotes that 9DOF orientation has locked to 6DOF
int8_t resetflag; // flag to request re-initialization on next pass int8_t resetflag; // flag to request re-initialization on next pass
}; };
#endif

View file

@ -296,9 +296,9 @@ void eigencompute(float A[][10], float eigval[], float eigvec[][10], int8_t n) {
A[ic][j] = A[ic][j] + sinphi * (ftmp - tanhalfphi * A[ic][j]); A[ic][j] = A[ic][j] + sinphi * (ftmp - tanhalfphi * A[ic][j]);
} }
} // end of test for matrix element already zero } // end of test for matrix element already zero
} // end of loop over columns } // end of loop over columns
} // end of loop over rows } // end of loop over rows
} // end of test for non-zero residue } // end of test for non-zero residue
} while ((residue > 0.0F) && (ctr++ < NITERATIONS)); // end of main loop } while ((residue > 0.0F) && (ctr++ < NITERATIONS)); // end of main loop
} }

View file

@ -1,16 +1,32 @@
/*!
* @file Adafruit_Simple_AHRS.cpp
*/
#include "Adafruit_Simple_AHRS.h" #include "Adafruit_Simple_AHRS.h"
// Create a simple AHRS from an explicit accelerometer and magnetometer sensor. /**************************************************************************/
/*!
* @brief Create a simple AHRS from a device with multiple sensors.
*/
/**************************************************************************/
Adafruit_Simple_AHRS::Adafruit_Simple_AHRS(Adafruit_Sensor *accelerometer, Adafruit_Simple_AHRS::Adafruit_Simple_AHRS(Adafruit_Sensor *accelerometer,
Adafruit_Sensor *magnetometer) Adafruit_Sensor *magnetometer)
: _accel(accelerometer), _mag(magnetometer) {} : _accel(accelerometer), _mag(magnetometer) {}
// Create a simple AHRS from a device with multiple sensors. /**************************************************************************/
/*!
* @brief Create a simple AHRS from a device with multiple sensors.
*/
/**************************************************************************/
Adafruit_Simple_AHRS::Adafruit_Simple_AHRS(Adafruit_Sensor_Set &sensors) Adafruit_Simple_AHRS::Adafruit_Simple_AHRS(Adafruit_Sensor_Set &sensors)
: _accel(sensors.getSensor(SENSOR_TYPE_ACCELEROMETER)), : _accel(sensors.getSensor(SENSOR_TYPE_ACCELEROMETER)),
_mag(sensors.getSensor(SENSOR_TYPE_MAGNETIC_FIELD)) {} _mag(sensors.getSensor(SENSOR_TYPE_MAGNETIC_FIELD)) {}
// Compute orientation based on accelerometer and magnetometer data. /**************************************************************************/
/*!
* @brief Compute orientation based on accelerometer and magnetometer data.
*/
/**************************************************************************/
bool Adafruit_Simple_AHRS::getOrientation(sensors_vec_t *orientation) { bool Adafruit_Simple_AHRS::getOrientation(sensors_vec_t *orientation) {
// Validate input and available sensors. // Validate input and available sensors.
if (orientation == NULL || _accel == NULL || _mag == NULL) if (orientation == NULL || _accel == NULL || _mag == NULL)
@ -82,4 +98,4 @@ bool Adafruit_Simple_AHRS::getOrientation(sensors_vec_t *orientation) {
orientation->heading = orientation->heading * 180 / PI_F; orientation->heading = orientation->heading * 180 / PI_F;
return true; return true;
} }

View file

@ -1,15 +1,45 @@
/*!
* @file Adafruit_Simple_AHRS.cpp
*/
#ifndef __ADAFRUIT_SIMPLE_AHRS_H__ #ifndef __ADAFRUIT_SIMPLE_AHRS_H__
#define __ADAFRUIT_SIMPLE_AHRS_H__ #define __ADAFRUIT_SIMPLE_AHRS_H__
#include "Adafruit_Sensor_Set.h" #include "Adafruit_Sensor_Set.h"
#include <Adafruit_Sensor.h> #include <Adafruit_Sensor.h>
// Simple sensor fusion AHRS using an accelerometer and magnetometer. /*!
* @brief Simple sensor fusion AHRS using an accelerometer and magnetometer.
*/
class Adafruit_Simple_AHRS { class Adafruit_Simple_AHRS {
public: public:
/**************************************************************************/
/*!
* @brief Create a simple AHRS from a device with multiple sensors.
*
* @param accelerometer The accelerometer to use for this sensor fusion.
* @param magnetometer The magnetometer to use for this sensor fusion.
*/
/**************************************************************************/
Adafruit_Simple_AHRS(Adafruit_Sensor *accelerometer, Adafruit_Simple_AHRS(Adafruit_Sensor *accelerometer,
Adafruit_Sensor *magnetometer); Adafruit_Sensor *magnetometer);
/**************************************************************************/
/*!
* @brief Create a simple AHRS from a device with multiple sensors.
*
* @param sensors A set of sensors containing the accelerometer and
* magnetometer for this sensor fusion.
*/
/**************************************************************************/
Adafruit_Simple_AHRS(Adafruit_Sensor_Set &sensors); Adafruit_Simple_AHRS(Adafruit_Sensor_Set &sensors);
/**************************************************************************/
/*!
* @brief Compute orientation based on accelerometer and magnetometer data.
*
* @return Whether the orientation was computed.
*/
/**************************************************************************/
bool getOrientation(sensors_vec_t *orientation); bool getOrientation(sensors_vec_t *orientation);
private: private: