From 6f20e11fabfe8c932f1b9a18ba679b99a9ce9565 Mon Sep 17 00:00:00 2001 From: lebarsfa Date: Sun, 20 Dec 2020 23:44:31 +0100 Subject: [PATCH] Added support for "OpenLog Artemis": DEV-16832 --- Arduino/Razor_AHRS/Razor_AHRS.ino | 96 ++++++++++---- Arduino/Razor_AHRS/Sensors.ino | 200 +++++++++++++++++++++++++++++- README.md | 12 +- 3 files changed, 277 insertions(+), 31 deletions(-) diff --git a/Arduino/Razor_AHRS/Razor_AHRS.ino b/Arduino/Razor_AHRS/Razor_AHRS.ino index 5f22555..6af33cc 100644 --- a/Arduino/Razor_AHRS/Razor_AHRS.ino +++ b/Arduino/Razor_AHRS/Razor_AHRS.ino @@ -1,14 +1,14 @@ /*************************************************************************************************************** * Razor AHRS Firmware * 9 Degree of Measurement Attitude and Heading Reference System -* for Sparkfun "9DOF Razor IMU" (SEN-10125 and SEN-10736) -* and "9DOF Sensor Stick" (SEN-10183, 10321 and SEN-10724) +* for Sparkfun "OpenLog Artemis" (DEV-16832), "9DoF Razor IMU M0" (SEN-14001), +* "9DOF Razor IMU" (SEN-10125 and SEN-10736) and "9DOF Sensor Stick" (SEN-10183, 10321 and SEN-10724) * * Released under GNU GPL (General Public License) v3.0 * Copyright (C) 2013 Peter Bartz [http://ptrbrtz.net] * Copyright (C) 2011-2012 Quality & Usability Lab, Deutsche Telekom Laboratories, TU Berlin * -* Infos, updates, bug reports, contributions and feedback: +* Original repository: * https://github.com/ptrbrtz/razor-9dof-ahrs * * @@ -44,7 +44,7 @@ * * Added static magnetometer soft iron distortion compensation. * * v1.4.2 * * (No core firmware changes) -* * v1.5 +* * v1.5.0 * * Added support for "9DoF Razor IMU M0": SEN-14001. * * v1.5.1 * * Added ROS-compatible output mode. @@ -64,19 +64,29 @@ * * Increased startup delay to try to get a correct initial orientation for the M0. * * v1.5.7 * * Calibration data are now also used to compute the initial orientation. +* * v1.6.0 +* * Added support for "OpenLog Artemis": DEV-16832. See OLA_IMU_Basics.ino sample from https://github.com/sparkfun/OpenLog_Artemis. +* * Added a command to toggle the status LED. * * TODOs: * * Allow optional use of Flash/EEPROM for storing and reading calibration values. * * Use self-test and temperature-compensation features of the sensors. ***************************************************************************************************************/ +/* + "OpenLog Artemis" hardware versions: DEV-16832 + + Arduino IDE : Follow the same instructions as for the default firmware on + https://github.com/sparkfun/OpenLog_Artemis/blob/master/Firmware/Test%20Sketches/OLA_IMU_Basics/OLA_IMU_Basics.ino +*/ + /* "9DoF Razor IMU M0" hardware versions: SEN-14001 Arduino IDE : Follow the same instructions as for the default firmware on https://learn.sparkfun.com/tutorials/9dof-razor-imu-m0-hookup-guide and use an updated version of SparkFun_MPU-9250-DMP_Arduino_Library from - https://github.com/lebarsfa/SparkFun_MPU-9250-DMP_Arduino_Library" + https://github.com/lebarsfa/SparkFun_MPU-9250-DMP_Arduino_Library */ /* @@ -102,8 +112,8 @@ */ /* - Axis definition (differs from definition printed on the board!): - X axis pointing forward (towards the short edge with the connector holes) + Axis definition (differs from definition printed on the board, see also https://github.com/Razor-AHRS/razor-9dof-ahrs/issues/57#issuecomment-378585065!): + X axis pointing forward (towards where "sparkfun" is written for DEV-16832 and SEN-14001, the short edge with the connector holes for SEN-10125 and SEN-10736) Y axis pointing to the right and Z axis pointing down. @@ -174,6 +184,9 @@ "#I" - Toggle INERTIAL-only mode for yaw computation. + "#L" - Toggle status LED. + + "#f" - Request one output frame - useful when continuous output is disabled and updates are required in larger intervals only. Though #f only requests one reply, replies are still bound to the internal 20ms (50Hz) time raster. So worst case delay that #f can add is 19.99ms. @@ -192,7 +205,7 @@ would set binary output mode, enable continuous streaming output and request a synch token all at once. - The status LED will be on if streaming output is enabled and off otherwise. + The status LED will be on if streaming output is enabled and off otherwise, unless "#L" is sent. Byte order of binary output is little-endian: least significant byte comes first. */ @@ -209,6 +222,7 @@ //#define HW__VERSION_CODE 10125 // SparkFun "9DOF Razor IMU" version "SEN-10125" (HMC5843 magnetometer) //#define HW__VERSION_CODE 10736 // SparkFun "9DOF Razor IMU" version "SEN-10736" (HMC5883L magnetometer) //#define HW__VERSION_CODE 14001 // SparkFun "9DoF Razor IMU M0" version "SEN-14001" +//#define HW__VERSION_CODE 16832 // SparkFun "OpenLog Artemis" version "DEV-16832" //#define HW__VERSION_CODE 10183 // SparkFun "9DOF Sensor Stick" version "SEN-10183" (HMC5843 magnetometer) //#define HW__VERSION_CODE 10321 // SparkFun "9DOF Sensor Stick" version "SEN-10321" (HMC5843 magnetometer) //#define HW__VERSION_CODE 10724 // SparkFun "9DOF Sensor Stick" version "SEN-10724" (HMC5883L magnetometer) @@ -218,12 +232,16 @@ /*****************************************************************/ // Set your serial port baud rate used to send out data here! #define OUTPUT__BAUD_RATE 57600 -#if HW__VERSION_CODE == 14001 // Set your port used to send out data here! +#if HW__VERSION_CODE == 16832 +#define LOG_PORT Serial +//#define LOG_PORT Serial1 +//Uart SerialLog(1, 13, 12); // Declares a Uart object called Serial1 using instance 1 of Apollo3 UART peripherals with RX on pin 13 and TX on pin 12 (note, you specify *pins* not Apollo3 pads. This uses the variant's pin map to determine the Apollo3 pad) +//#define LOG_PORT SerialLog +#elif HW__VERSION_CODE == 14001 #define LOG_PORT SERIAL_PORT_USBVIRTUAL //#define LOG_PORT SERIAL_PORT_HARDWARE #else -// Set your port used to send out data here! #define LOG_PORT Serial #endif // HW__VERSION_CODE @@ -268,7 +286,7 @@ boolean output_errors = false; // true or false // SENSOR CALIBRATION /*****************************************************************/ -// How to calibrate? Read the tutorial at http://dev.qu.tu-berlin.de/projects/sf-razor-9dof-ahrs +// How to calibrate? Read the tutorial at https://github.com/ptrbrtz/razor-9dof-ahrs/wiki/Tutorial // Put MIN/MAX and OFFSET readings for your board here! // For the M0, only the extended magnetometer calibration seems to be really necessary if DEBUG__USE_DMP_M0 is set to true... // Accelerometer @@ -383,7 +401,34 @@ boolean DEBUG__NO_DRIFT_CORRECTION = false; #error YOU HAVE TO SELECT THE HARDWARE YOU ARE USING! See "HARDWARE OPTIONS" in "USER SETUP AREA" at top of Razor_AHRS.ino! #endif -#if HW__VERSION_CODE == 14001 +#if HW__VERSION_CODE == 16832 +// OLA Specifics: +const byte PIN_IMU_POWER = 27; // The Red SparkFun version of the OLA (V10) uses pin 27 +//const byte PIN_IMU_POWER = 22; // The Black SparkX version of the OLA (X04) uses pin 22 +const byte PIN_IMU_INT = 37; +const byte PIN_IMU_CHIP_SELECT = 44; +// For low power... +const byte PIN_QWIIC_POWER = 18; +const byte PIN_MICROSD_POWER = 15; //x04 + +#include "ICM_20948.h" // Click here to get the library: http://librarymanager/All#SparkFun_ICM_20948_IMU + +#define USE_SPI // Uncomment this to use SPI + +#define SPI_PORT SPI // Your desired SPI port. Used only when "USE_SPI" is defined +#define CS_PIN PIN_IMU_CHIP_SELECT // Which pin you connect CS to. Used only when "USE_SPI" is defined. OLA uses pin 44. + +#define WIRE_PORT Wire // Your desired Wire port. Used when "USE_SPI" is not defined +#define AD0_VAL 1 // The value of the last bit of the I2C address. + // On the SparkFun 9DoF IMU breakout the default is 1, and when + // the ADR jumper is closed the value becomes 0 + +#ifdef USE_SPI + ICM_20948_SPI myICM; // If using SPI create an ICM_20948_SPI object +#else + ICM_20948_I2C myICM; // Otherwise create an ICM_20948_I2C object +#endif +#elif HW__VERSION_CODE == 14001 // MPU-9250 Digital Motion Processing (DMP) Library #include @@ -431,7 +476,7 @@ float MAGN_Z_SCALE = (100.0f / (MAGN_Z_MAX - MAGN_Z_OFFSET)); -#if HW__VERSION_CODE == 14001 +#if (HW__VERSION_CODE == 16832) || (HW__VERSION_CODE == 14001) #define GYRO_SCALED_RAD(x) (x) // Calculate the scaled gyro readings in radians per second #else // Gain for gyroscope (ITG-3200) @@ -445,8 +490,13 @@ float MAGN_Z_SCALE = (100.0f / (MAGN_Z_MAX - MAGN_Z_OFFSET)); #define Kp_YAW 1.2f #define Ki_YAW 0.00002f -// Stuff -#define STATUS_LED_PIN 13 // Pin number of status LED +// Pin number of status LED +#if (HW__VERSION_CODE == 16832) +#define STATUS_LED_PIN 19 +#else +#define STATUS_LED_PIN 13 +#endif // HW__VERSION_CODE + #define TO_RAD(x) (x * 0.01745329252) // *pi/180 #define TO_DEG(x) (x * 57.2957795131) // *180/pi @@ -499,7 +549,7 @@ int num_gyro_errors = 0; int num_math_errors = 0; void read_sensors() { -#if HW__VERSION_CODE == 14001 +#if (HW__VERSION_CODE == 16832) || (HW__VERSION_CODE == 14001) loop_imu(); #else Read_Gyro(); // Read gyroscope @@ -639,12 +689,8 @@ void setup() // Init sensors delay(50); // Give sensors enough time to start -#if HW__VERSION_CODE == 14001 -#if DEBUG__ENABLE_INTERRUPT_M0 == true - // Set up MPU-9250 interrupt input (active-low) - pinMode(MPU9250_INT_PIN, INPUT_PULLUP); -#endif // DEBUG__ENABLE_INTERRUPT_M0 - initIMU(); +#if (HW__VERSION_CODE == 16832) || (HW__VERSION_CODE == 14001) + beginIMU(); #else I2C_Init(); Accel_Init(); @@ -653,7 +699,7 @@ void setup() #endif // HW__VERSION_CODE // Read sensors, init DCM algorithm -#if HW__VERSION_CODE == 14001 +#if (HW__VERSION_CODE == 16832) || (HW__VERSION_CODE == 14001) delay(400); // Give sensors enough time to collect data #else delay(20); // Give sensors enough time to collect data @@ -944,6 +990,10 @@ void loop() initialimuyaw = imu.yaw*PI/180.0f; #endif // DEBUG__USE_ONLY_DMP_M0 } + else if (command == 'L') // Toggle status _L_ed + { + if (digitalRead(STATUS_LED_PIN) == HIGH) digitalWrite(STATUS_LED_PIN, LOW); else digitalWrite(STATUS_LED_PIN, HIGH); + } #if OUTPUT__HAS_RN_BLUETOOTH == true // Read messages from bluetooth module // For this to work, the connect/disconnect message prefix of the module has to be set to "#". diff --git a/Arduino/Razor_AHRS/Sensors.ino b/Arduino/Razor_AHRS/Sensors.ino index c59e2f9..7b9c316 100644 --- a/Arduino/Razor_AHRS/Sensors.ino +++ b/Arduino/Razor_AHRS/Sensors.ino @@ -1,6 +1,197 @@ /* This file is part of the Razor AHRS Firmware */ -#if HW__VERSION_CODE == 14001 +#if HW__VERSION_CODE == 16832 +bool imuAccDLPF = true; // IMU accelerometer Digital Low Pass Filter. +bool imuGyroDLPF = true; // IMU gyro Digital Low Pass Filter. +// IMU accelerometer full scale (ICM_20948_ACCEL_CONFIG_FS_SEL_e) +// 0: +/- 2g +// 1: +/- 4g +// 2: +/- 8g +// 3: +/- 16g +int imuAccFSS = gpm16; +// IMU accelerometer DLPF bandwidth (ICM_20948_ACCEL_CONFIG_DLPCFG_e) +// 0: 246.0 (3dB) 265.0 (Nyquist) (Hz) +// 1: 246.0 (3dB) 265.0 (Nyquist) (Hz) +// 2: 111.4 (3dB) 136.0 (Nyquist) (Hz) +// 3: 50.4 (3dB) 68.8 (Nyquist) (Hz) +// 4: 23.9 (3dB) 34.4 (Nyquist) (Hz) +// 5: 11.5 (3dB) 17.0 (Nyquist) (Hz) +// 6: 5.7 (3dB) 8.3 (Nyquist) (Hz) +// 7: 473 (3dB) 499 (Nyquist) (Hz) +int imuAccDLPFBW = 6;//acc_d50bw4_n68bw8; +// IMU gyro full scale (ICM_20948_GYRO_CONFIG_1_FS_SEL_e) +// 0: +/- 250dps +// 1: +/- 500dps +// 2: +/- 1000dps +// 3: +/- 2000dps +int imuGyroFSS = dps2000; +// IMU gyro DLPF bandwidth (ICM_20948_GYRO_CONFIG_1_DLPCFG_e) +// 0: 196.6 (3dB) 229.8 (Nyquist) (Hz) +// 1: 151.8 (3dB) 187.6 (Nyquist) (Hz) +// 2: 119.5 (3dB) 154.3 (Nyquist) (Hz) +// 3: 51.2 (3dB) 73.3 (Nyquist) (Hz) +// 4: 23.9 (3dB) 35.9 (Nyquist) (Hz) +// 5: 11.6 (3dB) 17.8 (Nyquist) (Hz) +// 6: 5.7 (3dB) 8.9 (Nyquist) (Hz) +// 7: 361.4 (3dB) 376.5 (Nyquist) (Hz) +int imuGyroDLPFBW = 6;//gyr_d51bw2_n73bw3; + +void qwiicPowerOn() +{ + pinMode(PIN_QWIIC_POWER, OUTPUT); + digitalWrite(PIN_QWIIC_POWER, LOW); +} + +void qwiicPowerOff() +{ + pinMode(PIN_QWIIC_POWER, OUTPUT); + digitalWrite(PIN_QWIIC_POWER, HIGH); +} + +void microSDPowerOn() +{ + pinMode(PIN_MICROSD_POWER, OUTPUT); + digitalWrite(PIN_MICROSD_POWER, LOW); +} + +void microSDPowerOff() +{ + pinMode(PIN_MICROSD_POWER, OUTPUT); + digitalWrite(PIN_MICROSD_POWER, HIGH); +} + +void imuPowerOn() +{ + pinMode(PIN_IMU_POWER, OUTPUT); + digitalWrite(PIN_IMU_POWER, HIGH); +} + +void imuPowerOff() +{ + pinMode(PIN_IMU_POWER, OUTPUT); + digitalWrite(PIN_IMU_POWER, LOW); +} + +bool enableCIPOpullUp() +{ + //Add CIPO pull-up + ap3_err_t retval = AP3_OK; + am_hal_gpio_pincfg_t cipoPinCfg = AP3_GPIO_DEFAULT_PINCFG; + cipoPinCfg.uFuncSel = AM_HAL_PIN_6_M0MISO; + cipoPinCfg.eDriveStrength = AM_HAL_GPIO_PIN_DRIVESTRENGTH_12MA; + cipoPinCfg.eGPOutcfg = AM_HAL_GPIO_PIN_OUTCFG_PUSHPULL; + cipoPinCfg.uIOMnum = AP3_SPI_IOM; + cipoPinCfg.ePullup = AM_HAL_GPIO_PIN_PULLUP_1_5K; + padMode(MISO, cipoPinCfg, &retval); + return (retval == AP3_OK); +} + +bool beginIMU(void) +{ + // For low power... + power_adc_disable(); // Power down ADC. It it started by default before setup(). + //Disable all pads + //for (int x = 0; x < 50; x++) + // am_hal_gpio_pinconfig(x, g_AM_HAL_GPIO_DISABLE); + pinMode(PIN_QWIIC_POWER, OUTPUT); + pinMode(PIN_MICROSD_POWER, OUTPUT); + qwiicPowerOff(); + microSDPowerOff(); + +#ifdef USE_SPI + SPI_PORT.begin(); +#else + WIRE_PORT.begin(); + WIRE_PORT.setClock(400000); +#endif + + enableCIPOpullUp(); // Enable CIPO pull-up on the OLA + + pinMode(PIN_IMU_CHIP_SELECT, OUTPUT); + digitalWrite(PIN_IMU_CHIP_SELECT, HIGH); //Be sure IMU is deselected + + //Reset ICM by power cycling it + imuPowerOff(); + + delay(10); + + imuPowerOn(); // Enable power for the OLA IMU + + delay(100); // Wait for the IMU to power up + + bool initialized = false; + while (!initialized) { +#ifdef USE_SPI + myICM.begin(CS_PIN, SPI_PORT); +#else + myICM.begin(WIRE_PORT, AD0_VAL); +#endif + if (myICM.status != ICM_20948_Stat_Ok) { + if (output_errors) LOG_PORT.println("!ERR: initializing ICM"); + delay(500); + } + else { + initialized = true; + } + } + + delay(25); // See https://github.com/sparkfun/OpenLog_Artemis/issues/18... + + if (myICM.enableDLPF(ICM_20948_Internal_Acc, imuAccDLPF) != ICM_20948_Stat_Ok) + { + if (output_errors) LOG_PORT.println("!ERR: configuring DLPF"); + } + if (myICM.enableDLPF(ICM_20948_Internal_Gyr, imuGyroDLPF) != ICM_20948_Stat_Ok) + { + if (output_errors) LOG_PORT.println("!ERR: configuring DLPF"); + } + ICM_20948_dlpcfg_t dlpcfg; + dlpcfg.a = imuAccDLPFBW; + dlpcfg.g = imuGyroDLPFBW; + if (myICM.setDLPFcfg((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), dlpcfg) != ICM_20948_Stat_Ok) + { + if (output_errors) LOG_PORT.println("!ERR: configuring DLPFBW"); + } + ICM_20948_fss_t FSS; + FSS.a = imuAccFSS; + FSS.g = imuGyroFSS; + if (myICM.setFullScale((ICM_20948_Internal_Acc | ICM_20948_Internal_Gyr), FSS) != ICM_20948_Stat_Ok) + { + if (output_errors) LOG_PORT.println("!ERR: configuring FSS"); + } + + return true; +} + +void loop_imu() +{ + if (!myICM.dataReady()) + { + num_accel_errors++; + if (output_errors) LOG_PORT.println("!ERR: reading accelerometer"); + num_gyro_errors++; + if (output_errors) LOG_PORT.println("!ERR: reading gyroscope"); + num_magn_errors++; + if (output_errors) LOG_PORT.println("!ERR: reading magnetometer"); + return; + } + + myICM.getAGMT(); // The values are only updated when you call 'getAGMT' + + // Conversion from g to similar unit as older versions of Razor... + accel[0] = 250.0f*myICM.accY()/1000.0; + accel[1] = 250.0f*myICM.accX()/1000.0; + accel[2] = 250.0f*myICM.accZ()/1000.0; + // Conversion from degrees/s to rad/s. + gyro[0] = -myICM.gyrY()*PI/180.0f; + gyro[1] = -myICM.gyrX()*PI/180.0f; + gyro[2] = -myICM.gyrZ()*PI/180.0f; + // Conversion from uT to mGauss. + magnetom[0] = (10.0f*myICM.magY()); + magnetom[1] = (-10.0f*myICM.magX()); + magnetom[2] = (10.0f*myICM.magZ()); +} +#elif HW__VERSION_CODE == 14001 /* * Known Bug - * DMP when enabled will sample sensor data at 200Hz and output to FIFO at the rate @@ -34,8 +225,13 @@ unsigned short accelFSR = IMU_ACCEL_FSR; unsigned short gyroFSR = IMU_GYRO_FSR; unsigned short fifoRate = DMP_SAMPLE_RATE; -bool initIMU(void) +bool beginIMU(void) { +#if DEBUG__ENABLE_INTERRUPT_M0 == true + // Set up MPU-9250 interrupt input (active-low) + pinMode(MPU9250_INT_PIN, INPUT_PULLUP); +#endif // DEBUG__ENABLE_INTERRUPT_M0 + // imu.begin() should return 0 on success. Will initialize // I2C bus, and reset MPU-9250 to defaults. if (imu.begin() != INV_SUCCESS) diff --git a/README.md b/README.md index aad35f5..3742fe8 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,9 @@ Razor AHRS --- -**9 Degree of Measurement Attitude and Heading Reference System** for Sparkfun *9DOF Razor IMU* (SEN-10125, SEN-10736 and SEN-14001) and SparkFun *9DOF Sensor Stick* (SEN-10183, SEN-10321 and SEN-10724) +**9 Degree of Measurement Attitude and Heading Reference System** for Sparkfun *OpenLog Artemis* (DEV-16832), *9DoF Razor IMU M0* (SEN-14001), *9DOF Razor IMU* (SEN-10125 and SEN-10736) and *9DOF Sensor Stick* (SEN-10183, SEN-10321 and SEN-10724) -Infos, updates, bug reports, contributions and feedback: https://github.com/ptrbrtz/razor-9dof-ahrs +Original repository : https://github.com/ptrbrtz/razor-9dof-ahrs Download --- @@ -13,9 +13,9 @@ Clone the [repository on GitHub](https://github.com/lebarsfa/razor-9dof-ahrs) or Tutorial --- -You find a [detailed tutorial in the Wiki](https://github.com/ptrbrtz/razor-9dof-ahrs/wiki/Tutorial). +You find a [detailed tutorial in the original Wiki](https://github.com/ptrbrtz/razor-9dof-ahrs/wiki/Tutorial). -Note: For SEN-14001 (*9DoF Razor IMU M0*), you will need to follow the same instructions as for the default firmware on https://learn.sparkfun.com/tutorials/9dof-razor-imu-m0-hookup-guide and use an updated version of SparkFun_MPU-9250-DMP_Arduino_Library from https://github.com/lebarsfa/SparkFun_MPU-9250-DMP_Arduino_Library (an updated version of the default firmware is also available on https://github.com/lebarsfa/9DOF_Razor_IMU). +Note: For DEV-16832 (*OpenLog Artemis*), you will need to follow the same instructions as for the `OLA_IMU_Basics.ino` sample from https://github.com/sparkfun/OpenLog_Artemis (i.e. get the drivers from https://learn.sparkfun.com/tutorials/how-to-install-ch340-drivers, install SparkFun Apollo3 boards in Arduino IDE as in https://learn.sparkfun.com/tutorials/installing-board-definitions-in-the-arduino-ide and ensure you select `SparkFun Apollo3` → `SparkFun RedBoard Artemis ATP` as the board and install SparkFun ICM 20948 IMU Arduino library as in https://learn.sparkfun.com/tutorials/installing-an-arduino-library). For SEN-14001 (*9DoF Razor IMU M0*), you will need to follow the same instructions as for the default firmware on https://learn.sparkfun.com/tutorials/9dof-razor-imu-m0-hookup-guide and use an updated version of SparkFun_MPU-9250-DMP_Arduino_Library from https://github.com/lebarsfa/SparkFun_MPU-9250-DMP_Arduino_Library (an updated version of the default firmware is also available on https://github.com/lebarsfa/9DOF_Razor_IMU). Quick setup --- @@ -28,7 +28,7 @@ Run `Processing/Razor_AHRS_test/Razor_AHRS_test.pde` using *Processing*. ### Optional: Mac OS X / Unix / Linux / Windows C++ Interface -Use the provided Qt project (check `Projects` → `Run Settings` → `Run in terminal` to force your application to run inside a separate terminal) or compile test program from the command line (add `-Iunix_adapt -DDISABLE_TIMEZONE_STRUCT_REDEFINITION -DENABLE_O_NDELAY_WORKAROUND` for MinGW/MSYS): +Use the provided *Qt Creator* project (check `Projects` → `Run Settings` → `Run in terminal` to force your application to run inside a separate terminal) or compile test program from the command line (add `-Iunix_adapt -DDISABLE_TIMEZONE_STRUCT_REDEFINITION -DENABLE_O_NDELAY_WORKAROUND` for MinGW/MSYS): g++ Example.cpp RazorAHRS.cpp -Wall -D_REENTRANT -lpthread -o example @@ -36,7 +36,7 @@ Run it: ./example -Note: To use the provided Visual Studio 2017 project, you will need to install Pthreads-win32 from http://www.ensta-bretagne.fr/lebars/Share/pthreads-win32-msvc.zip. +Note: To use the provided *Visual Studio 2017* project, you will need to install Pthreads-win32 from http://www.ensta-bretagne.fr/lebars/Share/pthreads-win32-msvc.zip. ### Optional: Android Interface