Home | History | Annotate | Download | only in mllite
      1 /*
      2  $License:
      3     Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
      4     See included License.txt for License information.
      5  $
      6  */
      7 
      8 /**
      9  *   @defgroup  HAL_Outputs hal_outputs
     10  *   @brief     Motion Library - HAL Outputs
     11  *              Sets up common outputs for HAL
     12  *
     13  *   @{
     14  *       @file  hal_outputs.c
     15  *       @brief HAL Outputs.
     16  */
     17 
     18 #undef MPL_LOG_NDEBUG
     19 #define MPL_LOG_NDEBUG 1 /* Use 0 to turn on MPL_LOGV output */
     20 #undef MPL_LOG_TAG
     21 #define MPL_LOG_TAG "MLLITE"
     22 //#define MPL_LOG_9AXIS_DEBUG 1
     23 
     24 #include <string.h>
     25 
     26 #include "hal_outputs.h"
     27 #include "log.h"
     28 #include "ml_math_func.h"
     29 #include "mlmath.h"
     30 #include "start_manager.h"
     31 #include "data_builder.h"
     32 #include "results_holder.h"
     33 
     34 /* commenting this define out will bypass the low pass filter noise reduction
     35    filter for compass data.
     36    Disable this only for testing purpose (e.g. comparing the raw and calibrated
     37    compass data, since the former is unfiltered and the latter is filtered,
     38    leading to a small difference in the readings sample by sample).
     39    Android specifications require this filter to be enabled to have the Magnetic
     40    Field output's standard deviation fall below 0.5 uT.
     41    */
     42 #define CALIB_COMPASS_NOISE_REDUCTION
     43 
     44 struct hal_output_t {
     45     int accuracy_mag;    /**< Compass accuracy */
     46     //int accuracy_gyro;   /**< Gyro Accuracy */
     47     //int accuracy_accel;  /**< Accel Accuracy */
     48     int accuracy_quat;   /**< quat Accuracy */
     49 
     50     inv_time_t nav_timestamp;
     51     inv_time_t gam_timestamp;
     52     //inv_time_t accel_timestamp;
     53     inv_time_t mag_timestamp;
     54     long nav_quat[4];
     55     int gyro_status;
     56     int accel_status;
     57     int compass_status;
     58     int nine_axis_status;
     59     int quat_status;
     60     inv_biquad_filter_t lp_filter[3];
     61     float compass_float[3];
     62     long linear_acceleration_sample_rate_us;
     63     long orientation_sample_rate_us;
     64     long rotation_vector_sample_rate_us;
     65     long gravity_sample_rate_us;
     66     long orientation_6_axis_sample_rate_us;
     67     long orientation_geomagnetic_sample_rate_us;
     68     long rotation_vector_6_axis_sample_rate_us;
     69     long geomagnetic_rotation_vector_sample_rate_us;
     70 };
     71 
     72 static struct hal_output_t hal_out;
     73 
     74 void inv_set_linear_acceleration_sample_rate(long sample_rate_us)
     75 {
     76     hal_out.linear_acceleration_sample_rate_us = sample_rate_us;
     77 }
     78 
     79 void inv_set_orientation_sample_rate(long sample_rate_us)
     80 {
     81     hal_out.orientation_sample_rate_us = sample_rate_us;
     82 }
     83 
     84 void inv_set_rotation_vector_sample_rate(long sample_rate_us)
     85 {
     86     hal_out.rotation_vector_sample_rate_us = sample_rate_us;
     87 }
     88 
     89 void inv_set_gravity_sample_rate(long sample_rate_us)
     90 {
     91     hal_out.gravity_sample_rate_us = sample_rate_us;
     92 }
     93 
     94 void inv_set_orientation_6_axis_sample_rate(long sample_rate_us)
     95 {
     96     hal_out.orientation_6_axis_sample_rate_us = sample_rate_us;
     97 }
     98 
     99 void inv_set_orientation_geomagnetic_sample_rate(long sample_rate_us)
    100 {
    101     hal_out.geomagnetic_rotation_vector_sample_rate_us = sample_rate_us;
    102 }
    103 
    104 void inv_set_rotation_vector_6_axis_sample_rate(long sample_rate_us)
    105 {
    106     hal_out.rotation_vector_6_axis_sample_rate_us = sample_rate_us;
    107 }
    108 
    109 void inv_set_geomagnetic_rotation_vector_sample_rate(long sample_rate_us)
    110 {
    111     hal_out.geomagnetic_rotation_vector_sample_rate_us = sample_rate_us;
    112 }
    113 
    114 /** Acceleration (m/s^2) in body frame.
    115 * @param[out] values Acceleration in m/s^2 includes gravity. So while not in motion, it
    116 *             should return a vector of magnitude near 9.81 m/s^2
    117 * @param[out] accuracy Accuracy of the measurment, 0 is least accurate, while 3 is most accurate.
    118 * @param[out] timestamp The timestamp for this sensor. Derived from the timestamp sent to
    119 *             inv_build_accel().
    120 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    121 */
    122 int inv_get_sensor_type_accelerometer(float *values, int8_t *accuracy,
    123                                        inv_time_t * timestamp)
    124 {
    125     int status;
    126     /* Converts fixed point to m/s^2. Fixed point has 1g = 2^16.
    127      * So this 9.80665 / 2^16 */
    128 #define ACCEL_CONVERSION 0.000149637603759766f
    129     long accel[3];
    130     inv_get_accel_set(accel, accuracy, timestamp);
    131     values[0] = accel[0] * ACCEL_CONVERSION;
    132     values[1] = accel[1] * ACCEL_CONVERSION;
    133     values[2] = accel[2] * ACCEL_CONVERSION;
    134     if (hal_out.accel_status & INV_NEW_DATA)
    135         status = 1;
    136     else
    137         status = 0;
    138     MPL_LOGV("accel values:%f %f %f -%d -%lld", values[0], values[1],
    139                               values[2], status, *timestamp);
    140     return status;
    141 }
    142 
    143 /** Linear Acceleration (m/s^2) in Body Frame.
    144 * @param[out] values Linear Acceleration in body frame, length 3, (m/s^2). May show
    145 *             accel biases while at rest.
    146 * @param[out] accuracy Accuracy of the measurment, 0 is least accurate, while 3 is most accurate.
    147 * @param[out] timestamp The timestamp for this sensor. Derived from the timestamp sent to
    148 *             inv_build_accel().
    149 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    150 */
    151 int inv_get_sensor_type_linear_acceleration(float *values, int8_t *accuracy,
    152         inv_time_t * timestamp)
    153 {
    154     long gravity[3], accel[3];
    155     inv_time_t timestamp1;
    156 
    157     inv_get_accel_set(accel, accuracy, &timestamp1);
    158     inv_get_gravity(gravity);
    159     accel[0] -= gravity[0] >> 14;
    160     accel[1] -= gravity[1] >> 14;
    161     accel[2] -= gravity[2] >> 14;
    162     values[0] = accel[0] * ACCEL_CONVERSION;
    163     values[1] = accel[1] * ACCEL_CONVERSION;
    164     values[2] = accel[2] * ACCEL_CONVERSION;
    165 
    166     return inv_get_6_axis_gyro_accel_timestamp(hal_out.linear_acceleration_sample_rate_us, timestamp);
    167 }
    168 
    169 /** Gravity vector (m/s^2) in Body Frame.
    170 * @param[out] values Gravity vector in body frame, length 3, (m/s^2)
    171 * @param[out] accuracy Accuracy of the measurment, 0 is least accurate, while 3 is most accurate.
    172 * @param[out] timestamp The timestamp for this sensor. Derived from the timestamp sent to
    173 *             inv_build_accel().
    174 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    175 */
    176 int inv_get_sensor_type_gravity(float *values, int8_t *accuracy,
    177                                  inv_time_t * timestamp)
    178 {
    179     long gravity[3];
    180 
    181     *accuracy = (int8_t) hal_out.accuracy_quat;
    182     inv_get_gravity(gravity);
    183     values[0] = (gravity[0] >> 14) * ACCEL_CONVERSION;
    184     values[1] = (gravity[1] >> 14) * ACCEL_CONVERSION;
    185     values[2] = (gravity[2] >> 14) * ACCEL_CONVERSION;
    186 
    187     return inv_get_6_axis_gyro_accel_timestamp(hal_out.gravity_sample_rate_us, timestamp);
    188 }
    189 
    190 /* Converts fixed point to rad/sec. Fixed point has 1 dps = 2^16.
    191  * So this is: pi / 2^16 / 180 */
    192 #define GYRO_CONVERSION 2.66316109007924e-007f
    193 
    194 /** Gyroscope calibrated data (rad/s) in body frame.
    195 * @param[out] values Rotation Rate in rad/sec.
    196 * @param[out] accuracy Accuracy of the measurment, 0 is least accurate, while 3 is most accurate.
    197 * @param[out] timestamp The timestamp for this sensor. Derived from the timestamp sent to
    198 *             inv_build_gyro().
    199 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    200 */
    201 int inv_get_sensor_type_gyroscope(float *values, int8_t *accuracy,
    202                                    inv_time_t * timestamp)
    203 {
    204     long gyro[3];
    205     int status;
    206 
    207     inv_get_gyro_set(gyro, accuracy, timestamp);
    208 
    209     values[0] = gyro[0] * GYRO_CONVERSION;
    210     values[1] = gyro[1] * GYRO_CONVERSION;
    211     values[2] = gyro[2] * GYRO_CONVERSION;
    212     if (hal_out.gyro_status & INV_NEW_DATA)
    213         status = 1;
    214     else
    215         status = 0;
    216     return status;
    217 }
    218 
    219 /** Gyroscope raw data (rad/s) in body frame.
    220 * @param[out] values Rotation Rate in rad/sec.
    221 * @param[out] accuracy Accuracy of the measurment, 0 is least accurate,
    222 *                      while 3 is most accurate.
    223 * @param[out] timestamp The timestamp for this sensor. Derived from the
    224 *                       timestamp sent to inv_build_gyro().
    225 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    226 */
    227 int inv_get_sensor_type_gyroscope_raw(float *values, int8_t *accuracy,
    228                                       inv_time_t * timestamp)
    229 {
    230     long gyro[3];
    231     int status;
    232 
    233     inv_get_gyro_set_raw(gyro, accuracy, timestamp);
    234     values[0] = gyro[0] * GYRO_CONVERSION;
    235     values[1] = gyro[1] * GYRO_CONVERSION;
    236     values[2] = gyro[2] * GYRO_CONVERSION;
    237     if (hal_out.gyro_status & INV_NEW_DATA)
    238         status = 1;
    239     else
    240         status = 0;
    241     return status;
    242 }
    243 
    244 /**
    245 * This corresponds to Sensor.TYPE_ROTATION_VECTOR.
    246 * The rotation vector represents the orientation of the device as a combination
    247 * of an angle and an axis, in which the device has rotated through an angle @f$\theta@f$
    248 * around an axis {x, y, z}. <br>
    249 * The three elements of the rotation vector are
    250 * {x*sin(@f$\theta@f$/2), y*sin(@f$\theta@f$/2), z*sin(@f$\theta@f$/2)}, such that the magnitude of the rotation
    251 * vector is equal to sin(@f$\theta@f$/2), and the direction of the rotation vector is
    252 * equal to the direction of the axis of rotation.
    253 *
    254 * The three elements of the rotation vector are equal to the last three components of a unit quaternion
    255 * {x*sin(@f$\theta@f$/2), y*sin(@f$\theta@f$/2), z*sin(@f$\theta@f$/2)>. The 4th element is cos(@f$\theta@f$/2).
    256 *
    257 * Elements of the rotation vector are unitless. The x,y and z axis are defined in the same way as the acceleration sensor.
    258 * The reference coordinate system is defined as a direct orthonormal basis, where:
    259 *
    260 *   -X is defined as the vector product Y.Z (It is tangential to the ground at the device's current location and roughly points East).
    261 *   -Y is tangential to the ground at the device's current location and points towards the magnetic North Pole.
    262 *   -Z points towards the sky and is perpendicular to the ground.
    263 * @param[out] values
    264 *               Length 5, 4th element being the w angle of the originating 4
    265 *               elements quaternion and 5th element being the heading accuracy
    266 *               at 95%.
    267 * @param[out] accuracy Accuracy is not defined
    268 * @param[out] timestamp Timestamp. In (ns) for Android.
    269 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    270 */
    271 int inv_get_sensor_type_rotation_vector(float *values, int8_t *accuracy,
    272         inv_time_t * timestamp)
    273 {
    274     float quat_float[4];
    275     *accuracy = (int8_t) hal_out.accuracy_quat;
    276     inv_get_quaternion_float(quat_float);
    277 
    278     if (quat_float[0] >= .0) {
    279         values[0] = quat_float[1];
    280         values[1] = quat_float[2];
    281         values[2] = quat_float[3];
    282         values[3] = quat_float[0];
    283     } else {
    284         values[0] = -quat_float[1];
    285         values[1] = -quat_float[2];
    286         values[2] = -quat_float[3];
    287         values[3] = -quat_float[0];
    288     }
    289     values[4] = inv_get_heading_confidence_interval();
    290     return inv_get_9_axis_timestamp(hal_out.rotation_vector_sample_rate_us, timestamp);
    291 }
    292 
    293 int inv_get_sensor_type_rotation_vector_6_axis(float *values, int8_t *accuracy,
    294         inv_time_t * timestamp)
    295 {
    296     int status;
    297     long accel[3];
    298     float quat_6_axis[4];
    299     inv_time_t timestamp1;
    300     inv_get_accel_set(accel, accuracy, &timestamp1);
    301     inv_get_6axis_quaternion_float(quat_6_axis, &timestamp1);
    302 
    303     if (quat_6_axis[0] >= .0) {
    304         values[0] = quat_6_axis[1];
    305         values[1] = quat_6_axis[2];
    306         values[2] = quat_6_axis[3];
    307         values[3] = quat_6_axis[0];
    308     } else {
    309         values[0] = -quat_6_axis[1];
    310         values[1] = -quat_6_axis[2];
    311         values[2] = -quat_6_axis[3];
    312         values[3] = -quat_6_axis[0];
    313     }
    314     //This sensor does not report an estimated heading accuracy
    315     values[4] = 0;
    316     if (hal_out.quat_status & INV_QUAT_3AXIS)
    317     {
    318         status = hal_out.quat_status & INV_NEW_DATA? 1 : 0;
    319     }
    320     else {
    321         status = hal_out.accel_status & INV_NEW_DATA? 1 : 0;
    322     }
    323     MPL_LOGV("values:%f %f %f %f %f -%d -%lld", values[0], values[1],
    324                               values[2], values[3], values[4], status, timestamp1);
    325     return inv_get_6_axis_gyro_accel_timestamp(hal_out.rotation_vector_6_axis_sample_rate_us, timestamp);
    326 }
    327 
    328 /**
    329 * This corresponds to Sensor.TYPE_GEOMAGNETIC_ROTATION_VECTOR.
    330 * Similar to SENSOR_TYPE_ROTATION_VECTOR, but using a magnetometer
    331 * instead of using a gyroscope.
    332 * Fourth element = estimated_accuracy in radians (heading confidence).
    333 * @param[out] values Length 4.
    334 * @param[out] accuracy is not defined.
    335 * @param[out] timestamp in (ns) for Android.
    336 * @return     Returns 1 if the data was updated, 0 otherwise.
    337 */
    338 int inv_get_sensor_type_geomagnetic_rotation_vector(float *values, int8_t *accuracy,
    339         inv_time_t * timestamp)
    340 {
    341     long compass[3];
    342     float quat_geomagnetic[4];
    343     int status;
    344     inv_time_t timestamp1;
    345     inv_get_compass_set(compass, accuracy, &timestamp1);
    346     inv_get_geomagnetic_quaternion_float(quat_geomagnetic, &timestamp1);
    347 
    348     if (quat_geomagnetic[0] >= .0) {
    349         values[0] = quat_geomagnetic[1];
    350         values[1] = quat_geomagnetic[2];
    351         values[2] = quat_geomagnetic[3];
    352         values[3] = quat_geomagnetic[0];
    353     } else {
    354         values[0] = -quat_geomagnetic[1];
    355         values[1] = -quat_geomagnetic[2];
    356         values[2] = -quat_geomagnetic[3];
    357         values[3] = -quat_geomagnetic[0];
    358     }
    359     values[4] = inv_get_accel_compass_confidence_interval();
    360     status = hal_out.accel_status & INV_NEW_DATA? 1 : 0;
    361     MPL_LOGV("values:%f %f %f %f %f -%d", values[0], values[1],
    362                               values[2], values[3], values[4], status);
    363 
    364     return inv_get_6_axis_compass_accel_timestamp(hal_out.geomagnetic_rotation_vector_sample_rate_us, timestamp);
    365 }
    366 
    367 /** Compass data (uT) in body frame.
    368 * @param[out] values Compass data in (uT), length 3. May be calibrated by having
    369 *             biases removed and sensitivity adjusted
    370 * @param[out] accuracy Accuracy 0 to 3, 3 = most accurate
    371 * @param[out] timestamp Timestamp. In (ns) for Android.
    372 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    373 */
    374 int inv_get_sensor_type_magnetic_field(float *values, int8_t *accuracy,
    375                                         inv_time_t * timestamp)
    376 {
    377     int status;
    378     int i;
    379     /* Converts fixed point to uT. Fixed point has 1 uT = 2^16.
    380      * So this is: 1 / 2^16*/
    381 //#define COMPASS_CONVERSION 1.52587890625e-005f
    382 
    383     *timestamp = hal_out.mag_timestamp;
    384     *accuracy = (int8_t) hal_out.accuracy_mag;
    385 
    386     for (i = 0; i < 3; i++)
    387         values[i] = hal_out.compass_float[i];
    388     if (hal_out.compass_status & INV_NEW_DATA)
    389         status = 1;
    390     else
    391         status = 0;
    392     return status;
    393 }
    394 
    395 /** Compass raw data (uT) in body frame.
    396 * @param[out] values Compass data in (uT), length 3. May be calibrated by having
    397 *             biases removed and sensitivity adjusted
    398 * @param[out] accuracy Accuracy 0 to 3, 3 = most accurate
    399 * @param[out] timestamp Timestamp. In (ns) for Android.
    400 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    401 */
    402 int inv_get_sensor_type_magnetic_field_raw(float *values, int8_t *accuracy,
    403                                            inv_time_t * timestamp)
    404 {
    405     long mag[3];
    406     int status;
    407     int i;
    408 
    409     inv_get_compass_set_raw(mag, accuracy, timestamp);
    410 
    411     /* Converts fixed point to uT. Fixed point has 1 uT = 2^16.
    412      * So this is: 1 / 2^16*/
    413 #define COMPASS_CONVERSION 1.52587890625e-005f
    414 
    415     for (i = 0; i < 3; i++) {
    416         values[i] = (float)mag[i] * COMPASS_CONVERSION;
    417     }
    418     if (hal_out.compass_status & INV_NEW_DATA)
    419         status = 1;
    420     else
    421         status = 0;
    422     return status;
    423 }
    424 static void inv_get_rotation_geomagnetic(float r[3][3])
    425 {
    426     long rot[9], quat_geo[4];
    427     float conv = 1.f / (1L<<30);
    428     inv_time_t timestamp;
    429     inv_get_geomagnetic_quaternion(quat_geo, &timestamp);
    430     inv_quaternion_to_rotation(quat_geo, rot);
    431     r[0][0] = rot[0]*conv;
    432     r[0][1] = rot[1]*conv;
    433     r[0][2] = rot[2]*conv;
    434     r[1][0] = rot[3]*conv;
    435     r[1][1] = rot[4]*conv;
    436     r[1][2] = rot[5]*conv;
    437     r[2][0] = rot[6]*conv;
    438     r[2][1] = rot[7]*conv;
    439     r[2][2] = rot[8]*conv;
    440 }
    441 static void google_orientation_geomagnetic(float *g)
    442 {
    443     float rad2deg = (float)(180.0 / M_PI);
    444     float R[3][3];
    445     inv_get_rotation_geomagnetic(R);
    446     g[0] = atan2f(-R[1][0], R[0][0]) * rad2deg;
    447     g[1] = atan2f(-R[2][1], R[2][2]) * rad2deg;
    448     g[2] = asinf ( R[2][0])          * rad2deg;
    449     if (g[0] < 0)
    450         g[0] += 360;
    451 }
    452 
    453 static void inv_get_rotation_6_axis(float r[3][3])
    454 {
    455     long rot[9], quat_6_axis[4];
    456     float conv = 1.f / (1L<<30);
    457     inv_time_t timestamp;
    458 
    459     inv_get_6axis_quaternion(quat_6_axis, &timestamp);
    460     inv_quaternion_to_rotation(quat_6_axis, rot);
    461     r[0][0] = rot[0]*conv;
    462     r[0][1] = rot[1]*conv;
    463     r[0][2] = rot[2]*conv;
    464     r[1][0] = rot[3]*conv;
    465     r[1][1] = rot[4]*conv;
    466     r[1][2] = rot[5]*conv;
    467     r[2][0] = rot[6]*conv;
    468     r[2][1] = rot[7]*conv;
    469     r[2][2] = rot[8]*conv;
    470 }
    471 
    472 static void google_orientation_6_axis(float *g)
    473 {
    474     float rad2deg = (float)(180.0 / M_PI);
    475     float R[3][3];
    476 
    477     inv_get_rotation_6_axis(R);
    478 
    479     g[0] = atan2f(-R[1][0], R[0][0]) * rad2deg;
    480     g[1] = atan2f(-R[2][1], R[2][2]) * rad2deg;
    481     g[2] = asinf ( R[2][0])          * rad2deg;
    482     if (g[0] < 0)
    483         g[0] += 360;
    484 }
    485 
    486 static void inv_get_rotation(float r[3][3])
    487 {
    488     long rot[9];
    489     float conv = 1.f / (1L<<30);
    490 
    491     inv_quaternion_to_rotation(hal_out.nav_quat, rot);
    492     r[0][0] = rot[0]*conv;
    493     r[0][1] = rot[1]*conv;
    494     r[0][2] = rot[2]*conv;
    495     r[1][0] = rot[3]*conv;
    496     r[1][1] = rot[4]*conv;
    497     r[1][2] = rot[5]*conv;
    498     r[2][0] = rot[6]*conv;
    499     r[2][1] = rot[7]*conv;
    500     r[2][2] = rot[8]*conv;
    501 }
    502 
    503 static void google_orientation(float *g)
    504 {
    505     float rad2deg = (float)(180.0 / M_PI);
    506     float R[3][3];
    507 
    508     inv_get_rotation(R);
    509 
    510     g[0] = atan2f(-R[1][0], R[0][0]) * rad2deg;
    511     g[1] = atan2f(-R[2][1], R[2][2]) * rad2deg;
    512     g[2] = asinf ( R[2][0])          * rad2deg;
    513     if (g[0] < 0)
    514         g[0] += 360;
    515 }
    516 
    517 /** This corresponds to Sensor.TYPE_ORIENTATION. All values are angles in degrees.
    518 * @param[out] values Length 3, Degrees.<br>
    519 *        - values[0]: Azimuth, angle between the magnetic north direction
    520 *         and the y-axis, around the z-axis (0 to 359). 0=North, 90=East, 180=South, 270=West<br>
    521 *        - values[1]: Pitch, rotation around x-axis (-180 to 180), with positive values
    522 *         when the z-axis moves toward the y-axis.<br>
    523 *        - values[2]: Roll, rotation around y-axis (-90 to 90), with positive
    524 *          values when the x-axis moves toward the z-axis.<br>
    525 *
    526 * @note  This definition is different from yaw, pitch and roll used in aviation
    527 *        where the X axis is along the long side of the plane (tail to nose).
    528 *        Note: This sensor type exists for legacy reasons, please use getRotationMatrix()
    529 *        in conjunction with remapCoordinateSystem() and getOrientation() to compute
    530 *        these values instead.
    531 *        Important note: For historical reasons the roll angle is positive in the
    532 *        clockwise direction (mathematically speaking, it should be positive in
    533 *        the counter-clockwise direction).
    534 * @param[out] accuracy Accuracy of the measurment, 0 is least accurate, while 3 is most accurate.
    535 * @param[out] timestamp The timestamp for this sensor.
    536 * @return     Returns 1 if the data was updated or 0 if it was not updated.
    537 */
    538 int inv_get_sensor_type_orientation(float *values, int8_t *accuracy,
    539                                      inv_time_t * timestamp)
    540 {
    541     *accuracy = (int8_t) hal_out.accuracy_quat;
    542     google_orientation(values);
    543 
    544     return inv_get_9_axis_timestamp(hal_out.orientation_sample_rate_us, timestamp);
    545 }
    546 
    547 int inv_get_sensor_type_orientation_6_axis(float *values, int8_t *accuracy,
    548                                      inv_time_t * timestamp)
    549 {
    550     long accel[3];
    551     inv_time_t timestamp1;
    552     inv_get_accel_set(accel, accuracy, &timestamp1);
    553 
    554     google_orientation_6_axis(values);
    555 
    556     return inv_get_6_axis_gyro_accel_timestamp(hal_out.orientation_6_axis_sample_rate_us, timestamp);
    557 }
    558 
    559 int inv_get_sensor_type_orientation_geomagnetic(float *values, int8_t *accuracy,
    560                                      inv_time_t * timestamp)
    561 {
    562     long compass[3];
    563     inv_time_t timestamp1;
    564     inv_get_compass_set(compass, accuracy, &timestamp1);
    565 
    566     google_orientation_geomagnetic(values);
    567 
    568     return inv_get_6_axis_compass_accel_timestamp(hal_out.orientation_geomagnetic_sample_rate_us, timestamp);
    569 }
    570 
    571 /** Main callback to generate HAL outputs. Typically not called by library users.
    572 * @param[in] sensor_cal Input variable to take sensor data whenever there is new
    573 * sensor data.
    574 * @return Returns INV_SUCCESS if successful or an error code if not.
    575 */
    576 inv_error_t inv_generate_hal_outputs(struct inv_sensor_cal_t *sensor_cal)
    577 {
    578     int use_sensor = 0;
    579     long sr = 1000;
    580     long compass[3];
    581     int8_t accuracy;
    582     int i;
    583     (void) sensor_cal;
    584 
    585     inv_get_quaternion_set(hal_out.nav_quat, &hal_out.accuracy_quat,
    586                            &hal_out.nav_timestamp);
    587     hal_out.gyro_status = sensor_cal->gyro.status;
    588     hal_out.accel_status = sensor_cal->accel.status;
    589     hal_out.compass_status = sensor_cal->compass.status;
    590     hal_out.quat_status = sensor_cal->quat.status;
    591 #if MPL_LOG_9AXIS_DEBUG
    592     MPL_LOGV("hal_out:g=%d", hal_out.gyro_status);
    593 #endif
    594     // Find the highest sample rate and tie generating 9-axis to that one.
    595     if (sensor_cal->gyro.status & INV_SENSOR_ON) {
    596         sr = sensor_cal->gyro.sample_rate_ms;
    597         use_sensor = 0;
    598     }
    599     if ((sensor_cal->accel.status & INV_SENSOR_ON) && (sr > sensor_cal->accel.sample_rate_ms)) {
    600         sr = sensor_cal->accel.sample_rate_ms;
    601         use_sensor = 1;
    602     }
    603     if ((sensor_cal->compass.status & INV_SENSOR_ON) && (sr > sensor_cal->compass.sample_rate_ms)) {
    604         sr = sensor_cal->compass.sample_rate_ms;
    605         use_sensor = 2;
    606     }
    607     if ((sensor_cal->quat.status & INV_SENSOR_ON) && (sr > sensor_cal->quat.sample_rate_ms)) {
    608         sr = sensor_cal->quat.sample_rate_ms;
    609         use_sensor = 3;
    610     }
    611 
    612     // If the timestamp did not change, remove the new data flag
    613     if (sensor_cal->gyro.timestamp_prev == sensor_cal->gyro.timestamp) {
    614         hal_out.gyro_status &= ~INV_NEW_DATA;
    615     }
    616     if (sensor_cal->accel.timestamp_prev == sensor_cal->accel.timestamp) {
    617         hal_out.accel_status &= ~INV_NEW_DATA;
    618     }
    619     if (sensor_cal->compass.timestamp_prev == sensor_cal->compass.timestamp) {
    620         hal_out.compass_status &= ~INV_NEW_DATA;
    621     }
    622     if (sensor_cal->quat.timestamp_prev == sensor_cal->quat.timestamp) {
    623         hal_out.quat_status &= ~INV_NEW_DATA;
    624     }
    625 
    626     // Only output 9-axis if all 9 sensors are on.
    627     if (sensor_cal->quat.status & INV_SENSOR_ON) {
    628         // If quaternion sensor is on, gyros are not required as quaternion already has that part
    629         if ((sensor_cal->accel.status & sensor_cal->compass.status & INV_SENSOR_ON) == 0) {
    630             use_sensor = -1;
    631         }
    632     } else {
    633         if ((sensor_cal->gyro.status & sensor_cal->accel.status & sensor_cal->compass.status & INV_SENSOR_ON) == 0) {
    634             use_sensor = -1;
    635         }
    636     }
    637 #if MPL_LOG_9AXIS_DEBUG
    638     MPL_LOGI("use_sensor=%d", use_sensor);
    639 #endif
    640     switch (use_sensor) {
    641     case 0:
    642         hal_out.nine_axis_status = (sensor_cal->gyro.status & INV_NEW_DATA) ? 1 : 0;
    643         hal_out.nav_timestamp = sensor_cal->gyro.timestamp;
    644         break;
    645     case 1:
    646         hal_out.nine_axis_status = (sensor_cal->accel.status & INV_NEW_DATA) ? 1 : 0;
    647         hal_out.nav_timestamp = sensor_cal->accel.timestamp;
    648         break;
    649     case 2:
    650         hal_out.nine_axis_status = (sensor_cal->compass.status & INV_NEW_DATA) ? 1 : 0;
    651         hal_out.nav_timestamp = sensor_cal->compass.timestamp;
    652         break;
    653     case 3:
    654         hal_out.nine_axis_status = (sensor_cal->quat.status & INV_NEW_DATA) ? 1 : 0;
    655         hal_out.nav_timestamp = sensor_cal->quat.timestamp;
    656         break;
    657     default:
    658         hal_out.nine_axis_status = 0; // Don't output quaternion related info
    659         break;
    660     }
    661 #if MPL_LOG_9AXIS_DEBUG
    662     MPL_LOGI("nav ts: %lld", hal_out.nav_timestamp);
    663 #endif
    664     /* Converts fixed point to uT. Fixed point has 1 uT = 2^16.
    665      * So this is: 1 / 2^16*/
    666     #define COMPASS_CONVERSION 1.52587890625e-005f
    667 
    668     inv_get_compass_set(compass, &accuracy, &(hal_out.mag_timestamp) );
    669     hal_out.accuracy_mag = (int)accuracy;
    670 
    671 #ifndef CALIB_COMPASS_NOISE_REDUCTION
    672     for (i = 0; i < 3; i++) {
    673         hal_out.compass_float[i] = (float)compass[i] * COMPASS_CONVERSION;
    674     }
    675 #else
    676     for (i = 0; i < 3; i++) {
    677         if ((sensor_cal->compass.status & (INV_NEW_DATA | INV_CONTIGUOUS)) ==
    678                                                              INV_NEW_DATA)  {
    679             // set the state variables to match output with input
    680             inv_calc_state_to_match_output(&hal_out.lp_filter[i],
    681                                            (float)compass[i]);
    682         }
    683         if ((sensor_cal->compass.status & (INV_NEW_DATA | INV_RAW_DATA)) ==
    684                                           (INV_NEW_DATA | INV_RAW_DATA)) {
    685             hal_out.compass_float[i] =
    686                 inv_biquad_filter_process(&hal_out.lp_filter[i],
    687                                           (float)compass[i]) *
    688                                           COMPASS_CONVERSION;
    689         } else if ((sensor_cal->compass.status & INV_NEW_DATA) == INV_NEW_DATA) {
    690             hal_out.compass_float[i] = (float)compass[i] * COMPASS_CONVERSION;
    691         }
    692     }
    693 #endif // CALIB_COMPASS_NOISE_REDUCTION
    694     return INV_SUCCESS;
    695 }
    696 
    697 /** Turns off generation of HAL outputs.
    698 * @return Returns INV_SUCCESS if successful or an error code if not.
    699  */
    700 inv_error_t inv_stop_hal_outputs(void)
    701 {
    702     inv_error_t result;
    703     result = inv_unregister_data_cb(inv_generate_hal_outputs);
    704     return result;
    705 }
    706 
    707 /** Turns on generation of HAL outputs. This should be called after inv_stop_hal_outputs()
    708 * to turn generation of HAL outputs back on. It is automatically called by inv_enable_hal_outputs().
    709 * @return Returns INV_SUCCESS if successful or an error code if not.
    710 */
    711 inv_error_t inv_start_hal_outputs(void)
    712 {
    713     inv_error_t result;
    714     result =
    715         inv_register_data_cb(inv_generate_hal_outputs,
    716                              INV_PRIORITY_HAL_OUTPUTS,
    717                              INV_GYRO_NEW | INV_ACCEL_NEW | INV_MAG_NEW | INV_QUAT_NEW | INV_PRESSURE_NEW);
    718     return result;
    719 }
    720 
    721 /* file name: lowPassFilterCoeff_1_6.c */
    722 float compass_low_pass_filter_coeff[5] =
    723 {+2.000000000000f, +1.000000000000f, -1.279632424998f, +0.477592250073f, +0.049489956269f};
    724 
    725 /** Initializes hal outputs class. This is called automatically by the
    726 * enable function. It may be called any time the feature is enabled, but
    727 * is typically not needed to be called by outside callers.
    728 * @return Returns INV_SUCCESS if successful or an error code if not.
    729 */
    730 inv_error_t inv_init_hal_outputs(void)
    731 {
    732     int i;
    733     memset(&hal_out, 0, sizeof(hal_out));
    734     for (i=0; i<3; i++)  {
    735         inv_init_biquad_filter(&hal_out.lp_filter[i], compass_low_pass_filter_coeff);
    736     }
    737 
    738     return INV_SUCCESS;
    739 }
    740 
    741 /** Turns on creation and storage of HAL type results.
    742 * @return Returns INV_SUCCESS if successful or an error code if not.
    743 */
    744 inv_error_t inv_enable_hal_outputs(void)
    745 {
    746     inv_error_t result;
    747 
    748         // don't need to check the result for inv_init_hal_outputs
    749         // since it's always INV_SUCCESS
    750         inv_init_hal_outputs();
    751 
    752     result = inv_register_mpl_start_notification(inv_start_hal_outputs);
    753     return result;
    754 }
    755 
    756 /** Turns off creation and storage of HAL type results.
    757 */
    758 inv_error_t inv_disable_hal_outputs(void)
    759 {
    760     inv_error_t result;
    761 
    762     inv_stop_hal_outputs(); // Ignore error if we have already stopped this
    763     result = inv_unregister_mpl_start_notification(inv_start_hal_outputs);
    764     return result;
    765 }
    766 
    767 /**
    768  * @}
    769  */
    770 
    771 
    772 
    773