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
This commit is contained in:
ToMe25 2021-02-09 17:41:23 +01:00 committed by GitHub
parent 1031b89cf1
commit a6eba1cb7b
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
7 changed files with 272 additions and 91 deletions

2
.gitignore vendored
View file

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

View file

@ -1,3 +1,21 @@
/*!
* @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_ #ifndef __ADAFRUIT_AHRS_H_
#define __ADAFRUIT_AHRS_H_ #define __ADAFRUIT_AHRS_H_

View file

@ -1,4 +1,8 @@
/* /*!
* @file Adafruit_AHRS_FusionInterface.h
*
* @section license License
*
* The MIT License (MIT) * The MIT License (MIT)
* *
* Copyright (c) 2020 Ha Thach (tinyusb.org) for Adafruit Industries * Copyright (c) 2020 Ha Thach (tinyusb.org) for Adafruit Industries
@ -25,15 +29,64 @@
#ifndef ADAFRUIT_AHRS_FUSIONINTERFACE_H_ #ifndef ADAFRUIT_AHRS_FUSIONINTERFACE_H_
#define ADAFRUIT_AHRS_FUSIONINTERFACE_H_ #define ADAFRUIT_AHRS_FUSIONINTERFACE_H_
// Interface for Fusion Algorithm /*!
* @brief The common interface for the fusion algorithms.
*/
class Adafruit_AHRS_FusionInterface { class Adafruit_AHRS_FusionInterface {
public: public:
/**************************************************************************/
/*!
* @brief Initializes the sensor fusion filter.
*
* @param sampleFrequency The sensor sample rate in herz(samples per second).
*/
/**************************************************************************/
virtual void begin(float sampleFrequency) = 0; 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, virtual void update(float gx, float gy, float gz, float ax, float ay,
float az, float mx, float my, float mz) = 0; 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; virtual float getRoll() = 0;
/**************************************************************************/
/*!
* @brief Gets the current pitch of the sensors.
*
* @return The current sensor pitch.
*/
/**************************************************************************/
virtual float getPitch() = 0; virtual float getPitch() = 0;
/**************************************************************************/
/*!
* @brief Gets the current yaw of the sensors.
*
* @return The current sensor yaw.
*/
/**************************************************************************/
virtual float getYaw() = 0; virtual float getYaw() = 0;
virtual void getQuaternion(float *w, float *x, float *y, float *z) = 0; virtual void getQuaternion(float *w, float *x, float *y, float *z) = 0;
}; };

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) {
@ -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];

View file

@ -1,47 +1,81 @@
#include "Adafruit_AHRS_FusionInterface.h" /*!
#include <Arduino.h> * @file Adafruit_AHRS_NXPFusion.h
*
// This is a modification of * @section license License
// https://github.com/memsindustrygroup/Open-Source-Sensor-Fusion/blob/master/Sources/tasks.h *
// by PJRC / Paul Stoffregen https://github.com/PaulStoffregen/NXPMotionSense * This is a modification of
* https://github.com/memsindustrygroup/Open-Source-Sensor-Fusion/blob/master/Sources/tasks.h
// Copyright (c) 2014, Freescale Semiconductor, Inc. * by PJRC / Paul Stoffregen https://github.com/PaulStoffregen/NXPMotionSense
// All rights reserved. *
// * Copyright (c) 2014, Freescale Semiconductor, Inc.
// Redistribution and use in source and binary forms, with or without * All rights reserved.
// modification, are permitted provided that the following conditions are met: *
// * Redistributions of source code must retain the above copyright * Redistribution and use in source and binary forms, with or without
// notice, this list of conditions and the following disclaimer. * modification, are permitted provided that the following conditions are met:
// * Redistributions in binary form must reproduce the above copyright * * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer in the * notice, this list of conditions and the following disclaimer.
// documentation and/or other materials provided with the distribution. * * Redistributions in binary form must reproduce the above copyright
// * Neither the name of Freescale Semiconductor, Inc. nor the * notice, this list of conditions and the following disclaimer in the
// names of its contributors may be used to endorse or promote products * documentation and/or other materials provided with the distribution.
// derived from this software without specific prior written permission. * * Neither the name of Freescale Semiconductor, Inc. nor the
// * names of its contributors may be used to endorse or promote products
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * derived from this software without specific prior written permission.
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE *
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * ARE DISCLAIMED. IN NO EVENT SHALL FREESCALE SEMICONDUCTOR, INC. BE LIABLE FOR
// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
// OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * 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_ #ifndef __Adafruit_Nxp_Fusion_h_
#define __Adafruit_Nxp_Fusion_h_ #define __Adafruit_Nxp_Fusion_h_
// changed class name to avoid collision #include "Adafruit_AHRS_FusionInterface.h"
#include <Arduino.h>
/*!
* @brief Kalman/NXP Fusion algorithm.
*/
class Adafruit_NXPSensorFusion : public Adafruit_AHRS_FusionInterface { class Adafruit_NXPSensorFusion : public Adafruit_AHRS_FusionInterface {
public: public:
void begin(float sampleRate = 100.0f); /**************************************************************************/
/* /*!
* For roll, pitch, and yaw the accelerometer values can be either m/s^2 or g, * @brief Initializes the 9DOF Kalman filter.
* but for linear acceleration to work they have to be in g. *
* @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);
@ -56,28 +90,46 @@ public:
*z = qPl.q3; *z = qPl.q3;
} }
/* /**************************************************************************/
* Get the linear acceleration part of the acceleration value given to update /*!
* in g. * @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 { void getLinearAcceleration(float *x, float *y, float *z) const {
*x = aSePl[0]; *x = aSePl[0];
*y = aSePl[1]; *y = aSePl[1];
*z = aSePl[2]; *z = aSePl[2];
} }
/** /**************************************************************************/
* The gravitational vector from the gyroscope values. /*!
* @brief Get the gravity vector from the gyroscope values.
*
* @param x The pointer to write the gravity vector x axis to. In g.
* @param y The pointer to write the gravity vector y axis to. In g.
* @param z The pointer to write the gravity vector z axis to. In g.
*/ */
/**************************************************************************/
void getGravityVector(float *x, float *y, float *z) const { void getGravityVector(float *x, float *y, float *z) const {
*x = gSeGyMi[0]; *x = gSeGyMi[0];
*y = gSeGyMi[1]; *y = gSeGyMi[1];
*z = gSeGyMi[2]; *z = gSeGyMi[2];
} }
/* /**************************************************************************/
* The global geomagnetic vector in uT. /*!
* @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 { void getGeomagneticVector(float *x, float *y, float *z) const {
*x = mGl[0]; *x = mGl[0];
*y = mGl[1]; *y = mGl[1];

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: