1
0

Razor_AHRS.ino 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849
  1. /***************************************************************************************************************
  2. * Razor AHRS Firmware v1.4.2.2
  3. * 9 Degree of Measurement Attitude and Heading Reference System
  4. * for Sparkfun "9DOF Razor IMU" (SEN-10125 and SEN-10736)
  5. * and "9DOF Sensor Stick" (SEN-10183, 10321 and SEN-10724)
  6. *
  7. * Released under GNU GPL (General Public License) v3.0
  8. * Copyright (C) 2013 Peter Bartz [http://ptrbrtz.net]
  9. * Copyright (C) 2011-2012 Quality & Usability Lab, Deutsche Telekom Laboratories, TU Berlin
  10. *
  11. * Infos, updates, bug reports, contributions and feedback:
  12. * https://github.com/ptrbrtz/razor-9dof-ahrs
  13. *
  14. *
  15. * History:
  16. * * Original code (http://code.google.com/p/sf9domahrs/) by Doug Weibel and Jose Julio,
  17. * based on ArduIMU v1.5 by Jordi Munoz and William Premerlani, Jose Julio and Doug Weibel. Thank you!
  18. *
  19. * * Updated code (http://groups.google.com/group/sf_9dof_ahrs_update) by David Malik (david.zsolt.malik@gmail.com)
  20. * for new Sparkfun 9DOF Razor hardware (SEN-10125).
  21. *
  22. * * Updated and extended by Peter Bartz (peter-bartz@gmx.de):
  23. * * v1.3.0
  24. * * Cleaned up, streamlined and restructured most of the code to make it more comprehensible.
  25. * * Added sensor calibration (improves precision and responsiveness a lot!).
  26. * * Added binary yaw/pitch/roll output.
  27. * * Added basic serial command interface to set output modes/calibrate sensors/synch stream/etc.
  28. * * Added support to synch automatically when using Rovering Networks Bluetooth modules (and compatible).
  29. * * Wrote new easier to use test program (using Processing).
  30. * * Added support for new version of "9DOF Razor IMU": SEN-10736.
  31. * --> The output of this code is not compatible with the older versions!
  32. * --> A Processing sketch to test the tracker is available.
  33. * * v1.3.1
  34. * * Initializing rotation matrix based on start-up sensor readings -> orientation OK right away.
  35. * * Adjusted gyro low-pass filter and output rate settings.
  36. * * v1.3.2
  37. * * Adapted code to work with new Arduino 1.0 (and older versions still).
  38. * * v1.3.3
  39. * * Improved synching.
  40. * * v1.4.0
  41. * * Added support for SparkFun "9DOF Sensor Stick" (versions SEN-10183, SEN-10321 and SEN-10724).
  42. * * v1.4.1
  43. * * Added output modes to read raw and/or calibrated sensor data in text or binary format.
  44. * * Added static magnetometer soft iron distortion compensation
  45. * * v1.4.2
  46. * * (No core firmware changes)
  47. * * v1.4.2.1
  48. * * New output mode to support ROS Imu use emits YPR + accel + rot. vel.
  49. * * v1.4.2.2
  50. * * New input mode to set calibration parameters
  51. *
  52. * TODOs:
  53. * * Allow optional use of EEPROM for storing and reading calibration values.
  54. * * Use self-test and temperature-compensation features of the sensors.
  55. ***************************************************************************************************************/
  56. /*
  57. "9DOF Razor IMU" hardware versions: SEN-10125 and SEN-10736
  58. ATMega328@3.3V, 8MHz
  59. ADXL345 : Accelerometer
  60. HMC5843 : Magnetometer on SEN-10125
  61. HMC5883L : Magnetometer on SEN-10736
  62. ITG-3200 : Gyro
  63. Arduino IDE : Select board "Arduino Pro or Pro Mini (3.3v, 8Mhz) w/ATmega328"
  64. */
  65. /*
  66. "9DOF Sensor Stick" hardware versions: SEN-10183, SEN-10321 and SEN-10724
  67. ADXL345 : Accelerometer
  68. HMC5843 : Magnetometer on SEN-10183 and SEN-10321
  69. HMC5883L : Magnetometer on SEN-10724
  70. ITG-3200 : Gyro
  71. */
  72. /*
  73. Axis definition (differs from definition printed on the board!):
  74. X axis pointing forward (towards the short edge with the connector holes)
  75. Y axis pointing to the right
  76. and Z axis pointing down.
  77. Positive yaw : clockwise
  78. Positive roll : right wing down
  79. Positive pitch : nose up
  80. Transformation order: first yaw then pitch then roll.
  81. */
  82. /*
  83. Serial commands that the firmware understands:
  84. "#c<params>" - SET _c_alibration parameters. The available options are:
  85. [a|m|g|c|t] _a_ccelerometer, _m_agnetometer, _g_yro, magnetometerellipsoid_c_enter, magnetometerellipsoid_t_ransform
  86. [x|y|z] x,y or z
  87. [m|M|X|Y|Z] _m_in or _M_ax (accel or magnetometer), X, Y, or Z of transform (magnetometerellipsoid_t_ransform)
  88. "#p" - PRINT current calibration values
  89. "#o<params>" - Set OUTPUT mode and parameters. The available options are:
  90. // Streaming output
  91. "#o0" - DISABLE continuous streaming output. Also see #f below.
  92. "#o1" - ENABLE continuous streaming output.
  93. // Angles output
  94. "#ob" - Output angles in BINARY format (yaw/pitch/roll as binary float, so one output frame
  95. is 3x4 = 12 bytes long).
  96. "#ot" - Output angles in TEXT format (Output frames have form like "#YPR=-142.28,-5.38,33.52",
  97. followed by carriage return and line feed [\r\n]).
  98. "#ox" - Output angles and linear acceleration and rotational
  99. velocity. Angles are in degrees, acceleration is
  100. in units of 1.0 = 1/256 G (9.8/256 m/s^2). Rotational
  101. velocity is in rad/s^2. (Output frames have form like
  102. "#YPRAG=-142.28,-5.38,33.52,0.1,0.1,1.0,0.01,0.01,0.01",
  103. followed by carriage return and line feed [\r\n]).
  104. // Sensor calibration
  105. "#oc" - Go to CALIBRATION output mode.
  106. "#on" - When in calibration mode, go on to calibrate NEXT sensor.
  107. // Sensor data output
  108. "#osct" - Output CALIBRATED SENSOR data of all 9 axes in TEXT format.
  109. One frame consist of three lines - one for each sensor: acc, mag, gyr.
  110. "#osrt" - Output RAW SENSOR data of all 9 axes in TEXT format.
  111. One frame consist of three lines - one for each sensor: acc, mag, gyr.
  112. "#osbt" - Output BOTH raw and calibrated SENSOR data of all 9 axes in TEXT format.
  113. One frame consist of six lines - like #osrt and #osct combined (first RAW, then CALIBRATED).
  114. NOTE: This is a lot of number-to-text conversion work for the little 8MHz chip on the Razor boards.
  115. In fact it's too much and an output frame rate of 50Hz can not be maintained. #osbb.
  116. "#oscb" - Output CALIBRATED SENSOR data of all 9 axes in BINARY format.
  117. One frame consist of three 3x3 float values = 36 bytes. Order is: acc x/y/z, mag x/y/z, gyr x/y/z.
  118. "#osrb" - Output RAW SENSOR data of all 9 axes in BINARY format.
  119. One frame consist of three 3x3 float values = 36 bytes. Order is: acc x/y/z, mag x/y/z, gyr x/y/z.
  120. "#osbb" - Output BOTH raw and calibrated SENSOR data of all 9 axes in BINARY format.
  121. One frame consist of 2x36 = 72 bytes - like #osrb and #oscb combined (first RAW, then CALIBRATED).
  122. // Error message output
  123. "#oe0" - Disable ERROR message output.
  124. "#oe1" - Enable ERROR message output.
  125. "#f" - Request one output frame - useful when continuous output is disabled and updates are
  126. required in larger intervals only. Though #f only requests one reply, replies are still
  127. bound to the internal 20ms (50Hz) time raster. So worst case delay that #f can add is 19.99ms.
  128. "#s<xy>" - Request synch token - useful to find out where the frame boundaries are in a continuous
  129. binary stream or to see if tracker is present and answering. The tracker will send
  130. "#SYNCH<xy>\r\n" in response (so it's possible to read using a readLine() function).
  131. x and y are two mandatory but arbitrary bytes that can be used to find out which request
  132. the answer belongs to.
  133. ("#C" and "#D" - Reserved for communication with optional Bluetooth module.)
  134. Newline characters are not required. So you could send "#ob#o1#s", which
  135. would set binary output mode, enable continuous streaming output and request
  136. a synch token all at once.
  137. The status LED will be on if streaming output is enabled and off otherwise.
  138. Byte order of binary output is little-endian: least significant byte comes first.
  139. */
  140. /*****************************************************************/
  141. /*********** USER SETUP AREA! Set your options here! *************/
  142. /*****************************************************************/
  143. // HARDWARE OPTIONS
  144. /*****************************************************************/
  145. // Select your hardware here by uncommenting one line!
  146. //#define HW__VERSION_CODE 10125 // SparkFun "9DOF Razor IMU" version "SEN-10125" (HMC5843 magnetometer)
  147. #define HW__VERSION_CODE 10736 // SparkFun "9DOF Razor IMU" version "SEN-10736" (HMC5883L magnetometer)
  148. //#define HW__VERSION_CODE 10183 // SparkFun "9DOF Sensor Stick" version "SEN-10183" (HMC5843 magnetometer)
  149. //#define HW__VERSION_CODE 10321 // SparkFun "9DOF Sensor Stick" version "SEN-10321" (HMC5843 magnetometer)
  150. //#define HW__VERSION_CODE 10724 // SparkFun "9DOF Sensor Stick" version "SEN-10724" (HMC5883L magnetometer)
  151. // OUTPUT OPTIONS
  152. /*****************************************************************/
  153. // Set your serial port baud rate used to send out data here!
  154. #define OUTPUT__BAUD_RATE 57600
  155. // Sensor data output interval in milliseconds
  156. // This may not work, if faster than 20ms (=50Hz)
  157. // Code is tuned for 20ms, so better leave it like that
  158. #define OUTPUT__DATA_INTERVAL 20 // in milliseconds
  159. // Output mode definitions (do not change)
  160. #define OUTPUT__MODE_CALIBRATE_SENSORS 0 // Outputs sensor min/max values as text for manual calibration
  161. #define OUTPUT__MODE_ANGLES 1 // Outputs yaw/pitch/roll in degrees
  162. #define OUTPUT__MODE_SENSORS_CALIB 2 // Outputs calibrated sensor values for all 9 axes
  163. #define OUTPUT__MODE_SENSORS_RAW 3 // Outputs raw (uncalibrated) sensor values for all 9 axes
  164. #define OUTPUT__MODE_SENSORS_BOTH 4 // Outputs calibrated AND raw sensor values for all 9 axes
  165. #define OUTPUT__MODE_ANGLES_AG_SENSORS 5 // Outputs yaw/pitch/roll in degrees + linear accel + rot. vel
  166. // Output format definitions (do not change)
  167. #define OUTPUT__FORMAT_TEXT 0 // Outputs data as text
  168. #define OUTPUT__FORMAT_BINARY 1 // Outputs data as binary float
  169. // Select your startup output mode and format here!
  170. int output_mode = OUTPUT__MODE_ANGLES;
  171. int output_format = OUTPUT__FORMAT_TEXT;
  172. // Select if serial continuous streaming output is enabled per default on startup.
  173. #define OUTPUT__STARTUP_STREAM_ON false // true or false
  174. // If set true, an error message will be output if we fail to read sensor data.
  175. // Message format: "!ERR: reading <sensor>", followed by "\r\n".
  176. boolean output_errors = false; // true or false
  177. // Bluetooth
  178. // You can set this to true, if you have a Rovering Networks Bluetooth Module attached.
  179. // The connect/disconnect message prefix of the module has to be set to "#".
  180. // (Refer to manual, it can be set like this: SO,#)
  181. // When using this, streaming output will only be enabled as long as we're connected. That way
  182. // receiver and sender are synchronzed easily just by connecting/disconnecting.
  183. // It is not necessary to set this! It just makes life easier when writing code for
  184. // the receiving side. The Processing test sketch also works without setting this.
  185. // NOTE: When using this, OUTPUT__STARTUP_STREAM_ON has no effect!
  186. #define OUTPUT__HAS_RN_BLUETOOTH false // true or false
  187. // SENSOR CALIBRATION
  188. /*****************************************************************/
  189. // How to calibrate? Read the tutorial at http://dev.qu.tu-berlin.de/projects/sf-razor-9dof-ahrs
  190. // Put MIN/MAX and OFFSET readings for your board here!
  191. // Accelerometer
  192. // "accel x,y,z (min/max) = X_MIN/X_MAX Y_MIN/Y_MAX Z_MIN/Z_MAX"
  193. float ACCEL_X_MIN = -250;
  194. float ACCEL_X_MAX = 250;
  195. float ACCEL_Y_MIN = -250;
  196. float ACCEL_Y_MAX = 250;
  197. float ACCEL_Z_MIN = -250;
  198. float ACCEL_Z_MAX = 250;
  199. // Magnetometer (standard calibration mode)
  200. // "magn x,y,z (min/max) = X_MIN/X_MAX Y_MIN/Y_MAX Z_MIN/Z_MAX"
  201. float MAGN_X_MIN = -600;
  202. float MAGN_X_MAX = 600;
  203. float MAGN_Y_MIN = -600;
  204. float MAGN_Y_MAX = 600;
  205. float MAGN_Z_MIN = -600;
  206. float MAGN_Z_MAX = 600;
  207. // Magnetometer (extended calibration mode)
  208. // Set to true to use extended magnetometer calibration (compensates hard & soft iron errors)
  209. boolean CALIBRATION__MAGN_USE_EXTENDED = false;
  210. float magn_ellipsoid_center[3] = {0, 0, 0};
  211. float magn_ellipsoid_transform[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}};
  212. // Gyroscope
  213. // "gyro x,y,z (current/average) = .../OFFSET_X .../OFFSET_Y .../OFFSET_Z
  214. float GYRO_AVERAGE_OFFSET_X = 0.0;
  215. float GYRO_AVERAGE_OFFSET_Y = 0.0;
  216. float GYRO_AVERAGE_OFFSET_Z = 0.0;
  217. // DEBUG OPTIONS
  218. /*****************************************************************/
  219. // When set to true, gyro drift correction will not be applied
  220. #define DEBUG__NO_DRIFT_CORRECTION false
  221. // Print elapsed time after each I/O loop
  222. #define DEBUG__PRINT_LOOP_TIME false
  223. /*****************************************************************/
  224. /****************** END OF USER SETUP AREA! *********************/
  225. /*****************************************************************/
  226. // Check if hardware version code is defined
  227. #ifndef HW__VERSION_CODE
  228. // Generate compile error
  229. #error YOU HAVE TO SELECT THE HARDWARE YOU ARE USING! See "HARDWARE OPTIONS" in "USER SETUP AREA" at top of Razor_AHRS.ino!
  230. #endif
  231. #include <Wire.h>
  232. #define GRAVITY 256.0f // "1G reference" used for DCM filter and accelerometer calibration
  233. // Sensor calibration scale and offset values
  234. float ACCEL_X_OFFSET = ((ACCEL_X_MIN + ACCEL_X_MAX) / 2.0f);
  235. float ACCEL_Y_OFFSET = ((ACCEL_Y_MIN + ACCEL_Y_MAX) / 2.0f);
  236. float ACCEL_Z_OFFSET = ((ACCEL_Z_MIN + ACCEL_Z_MAX) / 2.0f);
  237. float ACCEL_X_SCALE = (GRAVITY / (ACCEL_X_MAX - ACCEL_X_OFFSET));
  238. float ACCEL_Y_SCALE = (GRAVITY / (ACCEL_Y_MAX - ACCEL_Y_OFFSET));
  239. float ACCEL_Z_SCALE = (GRAVITY / (ACCEL_Z_MAX - ACCEL_Z_OFFSET));
  240. float MAGN_X_OFFSET = ((MAGN_X_MIN + MAGN_X_MAX) / 2.0f);
  241. float MAGN_Y_OFFSET = ((MAGN_Y_MIN + MAGN_Y_MAX) / 2.0f);
  242. float MAGN_Z_OFFSET = ((MAGN_Z_MIN + MAGN_Z_MAX) / 2.0f);
  243. float MAGN_X_SCALE = (100.0f / (MAGN_X_MAX - MAGN_X_OFFSET));
  244. float MAGN_Y_SCALE = (100.0f / (MAGN_Y_MAX - MAGN_Y_OFFSET));
  245. float MAGN_Z_SCALE = (100.0f / (MAGN_Z_MAX - MAGN_Z_OFFSET));
  246. // Gain for gyroscope (ITG-3200)
  247. #define GYRO_GAIN 0.06957 // Same gain on all axes
  248. #define GYRO_SCALED_RAD(x) (x * TO_RAD(GYRO_GAIN)) // Calculate the scaled gyro readings in radians per second
  249. // DCM parameters
  250. #define Kp_ROLLPITCH 0.02f
  251. #define Ki_ROLLPITCH 0.00002f
  252. #define Kp_YAW 1.2f
  253. #define Ki_YAW 0.00002f
  254. // Stuff
  255. #define STATUS_LED_PIN 13 // Pin number of status LED
  256. #define TO_RAD(x) (x * 0.01745329252) // *pi/180
  257. #define TO_DEG(x) (x * 57.2957795131) // *180/pi
  258. // Sensor variables
  259. float accel[3]; // Actually stores the NEGATED acceleration (equals gravity, if board not moving).
  260. float accel_min[3];
  261. float accel_max[3];
  262. float magnetom[3];
  263. float magnetom_min[3];
  264. float magnetom_max[3];
  265. float magnetom_tmp[3];
  266. float gyro[3];
  267. float gyro_average[3];
  268. int gyro_num_samples = 0;
  269. // DCM variables
  270. float MAG_Heading;
  271. float Accel_Vector[3]= {0, 0, 0}; // Store the acceleration in a vector
  272. float Gyro_Vector[3]= {0, 0, 0}; // Store the gyros turn rate in a vector
  273. float Omega_Vector[3]= {0, 0, 0}; // Corrected Gyro_Vector data
  274. float Omega_P[3]= {0, 0, 0}; // Omega Proportional correction
  275. float Omega_I[3]= {0, 0, 0}; // Omega Integrator
  276. float Omega[3]= {0, 0, 0};
  277. float errorRollPitch[3] = {0, 0, 0};
  278. float errorYaw[3] = {0, 0, 0};
  279. float DCM_Matrix[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}};
  280. float Update_Matrix[3][3] = {{0, 1, 2}, {3, 4, 5}, {6, 7, 8}};
  281. float Temporary_Matrix[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}};
  282. // Euler angles
  283. float yaw;
  284. float pitch;
  285. float roll;
  286. // DCM timing in the main loop
  287. unsigned long timestamp;
  288. unsigned long timestamp_old;
  289. float G_Dt; // Integration time for DCM algorithm
  290. // More output-state variables
  291. boolean output_stream_on;
  292. boolean output_single_on;
  293. int curr_calibration_sensor = 0;
  294. boolean reset_calibration_session_flag = true;
  295. int num_accel_errors = 0;
  296. int num_magn_errors = 0;
  297. int num_gyro_errors = 0;
  298. void read_sensors() {
  299. Read_Gyro(); // Read gyroscope
  300. Read_Accel(); // Read accelerometer
  301. Read_Magn(); // Read magnetometer
  302. }
  303. //should be called after every #ca calibration command
  304. void recalculateAccelCalibration(){
  305. ACCEL_X_OFFSET = ((ACCEL_X_MIN + ACCEL_X_MAX) / 2.0f);
  306. ACCEL_Y_OFFSET = ((ACCEL_Y_MIN + ACCEL_Y_MAX) / 2.0f);
  307. ACCEL_Z_OFFSET = ((ACCEL_Z_MIN + ACCEL_Z_MAX) / 2.0f);
  308. ACCEL_X_SCALE = (GRAVITY / (ACCEL_X_MAX - ACCEL_X_OFFSET));
  309. ACCEL_Y_SCALE = (GRAVITY / (ACCEL_Y_MAX - ACCEL_Y_OFFSET));
  310. ACCEL_Z_SCALE = (GRAVITY / (ACCEL_Z_MAX - ACCEL_Z_OFFSET));
  311. }
  312. //should be called after every #cm calibration command
  313. void recalculateMagnCalibration(){
  314. MAGN_X_OFFSET = ((MAGN_X_MIN + MAGN_X_MAX) / 2.0f);
  315. MAGN_Y_OFFSET = ((MAGN_Y_MIN + MAGN_Y_MAX) / 2.0f);
  316. MAGN_Z_OFFSET = ((MAGN_Z_MIN + MAGN_Z_MAX) / 2.0f);
  317. MAGN_X_SCALE = (100.0f / (MAGN_X_MAX - MAGN_X_OFFSET));
  318. MAGN_Y_SCALE = (100.0f / (MAGN_Y_MAX - MAGN_Y_OFFSET));
  319. MAGN_Z_SCALE = (100.0f / (MAGN_Z_MAX - MAGN_Z_OFFSET));
  320. }
  321. // Read every sensor and record a time stamp
  322. // Init DCM with unfiltered orientation
  323. // TODO re-init global vars?
  324. void reset_sensor_fusion() {
  325. float temp1[3];
  326. float temp2[3];
  327. float xAxis[] = {1.0f, 0.0f, 0.0f};
  328. read_sensors();
  329. timestamp = millis();
  330. // GET PITCH
  331. // Using y-z-plane-component/x-component of gravity vector
  332. pitch = -atan2(accel[0], sqrt(accel[1] * accel[1] + accel[2] * accel[2]));
  333. // GET ROLL
  334. // Compensate pitch of gravity vector
  335. Vector_Cross_Product(temp1, accel, xAxis);
  336. Vector_Cross_Product(temp2, xAxis, temp1);
  337. // Normally using x-z-plane-component/y-component of compensated gravity vector
  338. // roll = atan2(temp2[1], sqrt(temp2[0] * temp2[0] + temp2[2] * temp2[2]));
  339. // Since we compensated for pitch, x-z-plane-component equals z-component:
  340. roll = atan2(temp2[1], temp2[2]);
  341. // GET YAW
  342. Compass_Heading();
  343. yaw = MAG_Heading;
  344. // Init rotation matrix
  345. init_rotation_matrix(DCM_Matrix, yaw, pitch, roll);
  346. }
  347. // Apply calibration to raw sensor readings
  348. void compensate_sensor_errors() {
  349. // Compensate accelerometer error
  350. accel[0] = (accel[0] - ACCEL_X_OFFSET) * ACCEL_X_SCALE;
  351. accel[1] = (accel[1] - ACCEL_Y_OFFSET) * ACCEL_Y_SCALE;
  352. accel[2] = (accel[2] - ACCEL_Z_OFFSET) * ACCEL_Z_SCALE;
  353. // Compensate magnetometer error
  354. if (CALIBRATION__MAGN_USE_EXTENDED){
  355. for (int i = 0; i < 3; i++)
  356. magnetom_tmp[i] = magnetom[i] - magn_ellipsoid_center[i];
  357. Matrix_Vector_Multiply(magn_ellipsoid_transform, magnetom_tmp, magnetom);
  358. }else{
  359. magnetom[0] = (magnetom[0] - MAGN_X_OFFSET) * MAGN_X_SCALE;
  360. magnetom[1] = (magnetom[1] - MAGN_Y_OFFSET) * MAGN_Y_SCALE;
  361. magnetom[2] = (magnetom[2] - MAGN_Z_OFFSET) * MAGN_Z_SCALE;
  362. }
  363. // Compensate gyroscope error
  364. gyro[0] -= GYRO_AVERAGE_OFFSET_X;
  365. gyro[1] -= GYRO_AVERAGE_OFFSET_Y;
  366. gyro[2] -= GYRO_AVERAGE_OFFSET_Z;
  367. }
  368. // Reset calibration session if reset_calibration_session_flag is set
  369. void check_reset_calibration_session()
  370. {
  371. // Raw sensor values have to be read already, but no error compensation applied
  372. // Reset this calibration session?
  373. if (!reset_calibration_session_flag) return;
  374. // Reset acc and mag calibration variables
  375. for (int i = 0; i < 3; i++) {
  376. accel_min[i] = accel_max[i] = accel[i];
  377. magnetom_min[i] = magnetom_max[i] = magnetom[i];
  378. }
  379. // Reset gyro calibration variables
  380. gyro_num_samples = 0; // Reset gyro calibration averaging
  381. gyro_average[0] = gyro_average[1] = gyro_average[2] = 0.0f;
  382. reset_calibration_session_flag = false;
  383. }
  384. void turn_output_stream_on()
  385. {
  386. output_stream_on = true;
  387. digitalWrite(STATUS_LED_PIN, HIGH);
  388. }
  389. void turn_output_stream_off()
  390. {
  391. output_stream_on = false;
  392. digitalWrite(STATUS_LED_PIN, LOW);
  393. }
  394. // Blocks until another byte is available on serial port
  395. char readChar()
  396. {
  397. while (Serial.available() < 1) { } // Block
  398. return Serial.read();
  399. }
  400. void setup()
  401. {
  402. // Init serial output
  403. Serial.begin(OUTPUT__BAUD_RATE);
  404. // Init status LED
  405. pinMode (STATUS_LED_PIN, OUTPUT);
  406. digitalWrite(STATUS_LED_PIN, LOW);
  407. // Init sensors
  408. delay(50); // Give sensors enough time to start
  409. I2C_Init();
  410. Accel_Init();
  411. Magn_Init();
  412. Gyro_Init();
  413. // Read sensors, init DCM algorithm
  414. delay(20); // Give sensors enough time to collect data
  415. reset_sensor_fusion();
  416. // Init output
  417. #if (OUTPUT__HAS_RN_BLUETOOTH == true) || (OUTPUT__STARTUP_STREAM_ON == false)
  418. turn_output_stream_off();
  419. #else
  420. turn_output_stream_on();
  421. #endif
  422. }
  423. // Main loop
  424. void loop()
  425. {
  426. // Read incoming control messages
  427. if (Serial.available() >= 2)
  428. {
  429. if (Serial.read() == '#') // Start of new control message
  430. {
  431. int command = Serial.read(); // Commands
  432. if (command == 'f') // request one output _f_rame
  433. output_single_on = true;
  434. else if (command == 's') // _s_ynch request
  435. {
  436. // Read ID
  437. byte id[2];
  438. id[0] = readChar();
  439. id[1] = readChar();
  440. // Reply with synch message
  441. Serial.print("#SYNCH");
  442. Serial.write(id, 2);
  443. Serial.println();
  444. }
  445. else if (command == 'o') // Set _o_utput mode
  446. {
  447. char output_param = readChar();
  448. if (output_param == 'n') // Calibrate _n_ext sensor
  449. {
  450. curr_calibration_sensor = (curr_calibration_sensor + 1) % 3;
  451. reset_calibration_session_flag = true;
  452. }
  453. else if (output_param == 't') // Output angles as _t_ext
  454. {
  455. output_mode = OUTPUT__MODE_ANGLES;
  456. output_format = OUTPUT__FORMAT_TEXT;
  457. }
  458. else if (output_param == 'b') // Output angles in _b_inary format
  459. {
  460. output_mode = OUTPUT__MODE_ANGLES;
  461. output_format = OUTPUT__FORMAT_BINARY;
  462. }
  463. else if (output_param == 'c') // Go to _c_alibration mode
  464. {
  465. output_mode = OUTPUT__MODE_CALIBRATE_SENSORS;
  466. reset_calibration_session_flag = true;
  467. }
  468. else if (output_param == 'x') // Go to _c_alibration mode for both sensor and angle comment: Tang
  469. {
  470. output_mode = OUTPUT__MODE_ANGLES_AG_SENSORS;
  471. reset_calibration_session_flag = true;
  472. }
  473. else if (output_param == 's') // Output _s_ensor values
  474. {
  475. char values_param = readChar();
  476. char format_param = readChar();
  477. if (values_param == 'r') // Output _r_aw sensor values
  478. output_mode = OUTPUT__MODE_SENSORS_RAW;
  479. else if (values_param == 'c') // Output _c_alibrated sensor values
  480. output_mode = OUTPUT__MODE_SENSORS_CALIB;
  481. else if (values_param == 'b') // Output _b_oth sensor values (raw and calibrated)
  482. output_mode = OUTPUT__MODE_SENSORS_BOTH;
  483. if (format_param == 't') // Output values as _t_text
  484. output_format = OUTPUT__FORMAT_TEXT;
  485. else if (format_param == 'b') // Output values in _b_inary format
  486. output_format = OUTPUT__FORMAT_BINARY;
  487. }
  488. else if (output_param == '0') // Disable continuous streaming output
  489. {
  490. turn_output_stream_off();
  491. reset_calibration_session_flag = true;
  492. }
  493. else if (output_param == '1') // Enable continuous streaming output
  494. {
  495. reset_calibration_session_flag = true;
  496. turn_output_stream_on();
  497. }
  498. else if (output_param == 'e') // _e_rror output settings
  499. {
  500. char error_param = readChar();
  501. if (error_param == '0') output_errors = false;
  502. else if (error_param == '1') output_errors = true;
  503. else if (error_param == 'c') // get error count
  504. {
  505. Serial.print("#AMG-ERR:");
  506. Serial.print(num_accel_errors); Serial.print(",");
  507. Serial.print(num_magn_errors); Serial.print(",");
  508. Serial.println(num_gyro_errors);
  509. }
  510. }
  511. }
  512. else if (command == 'p') // Set _p_rint calibration values
  513. {
  514. Serial.print("ACCEL_X_MIN:");Serial.println(ACCEL_X_MIN);
  515. Serial.print("ACCEL_X_MAX:");Serial.println(ACCEL_X_MAX);
  516. Serial.print("ACCEL_Y_MIN:");Serial.println(ACCEL_Y_MIN);
  517. Serial.print("ACCEL_Y_MAX:");Serial.println(ACCEL_Y_MAX);
  518. Serial.print("ACCEL_Z_MIN:");Serial.println(ACCEL_Z_MIN);
  519. Serial.print("ACCEL_Z_MAX:");Serial.println(ACCEL_Z_MAX);
  520. Serial.println("");
  521. Serial.print("MAGN_X_MIN:");Serial.println(MAGN_X_MIN);
  522. Serial.print("MAGN_X_MAX:");Serial.println(MAGN_X_MAX);
  523. Serial.print("MAGN_Y_MIN:");Serial.println(MAGN_Y_MIN);
  524. Serial.print("MAGN_Y_MAX:");Serial.println(MAGN_Y_MAX);
  525. Serial.print("MAGN_Z_MIN:");Serial.println(MAGN_Z_MIN);
  526. Serial.print("MAGN_Z_MAX:");Serial.println(MAGN_Z_MAX);
  527. Serial.println("");
  528. Serial.print("MAGN_USE_EXTENDED:");
  529. if (CALIBRATION__MAGN_USE_EXTENDED)
  530. Serial.println("true");
  531. else
  532. Serial.println("false");
  533. Serial.print("magn_ellipsoid_center:[");Serial.print(magn_ellipsoid_center[0],4);Serial.print(",");
  534. Serial.print(magn_ellipsoid_center[1],4);Serial.print(",");
  535. Serial.print(magn_ellipsoid_center[2],4);Serial.println("]");
  536. Serial.print("magn_ellipsoid_transform:[");
  537. for(int i = 0; i < 3; i++){
  538. Serial.print("[");
  539. for(int j = 0; j < 3; j++){
  540. Serial.print(magn_ellipsoid_transform[i][j],7);
  541. if (j < 2) Serial.print(",");
  542. }
  543. Serial.print("]");
  544. if (i < 2) Serial.print(",");
  545. }
  546. Serial.println("]");
  547. Serial.println("");
  548. Serial.print("GYRO_AVERAGE_OFFSET_X:");Serial.println(GYRO_AVERAGE_OFFSET_X);
  549. Serial.print("GYRO_AVERAGE_OFFSET_Y:");Serial.println(GYRO_AVERAGE_OFFSET_Y);
  550. Serial.print("GYRO_AVERAGE_OFFSET_Z:");Serial.println(GYRO_AVERAGE_OFFSET_Z);
  551. }
  552. else if (command == 'c') // Set _i_nput mode
  553. {
  554. char input_param = readChar();
  555. if (input_param == 'a') // Calibrate _a_ccelerometer
  556. {
  557. char axis_param = readChar();
  558. char type_param = readChar();
  559. float value_param = Serial.parseFloat();
  560. if (axis_param == 'x') // x value
  561. {
  562. if (type_param == 'm')
  563. ACCEL_X_MIN = value_param;
  564. else if (type_param == 'M')
  565. ACCEL_X_MAX = value_param;
  566. }
  567. else if (axis_param == 'y') // y value
  568. {
  569. if (type_param == 'm')
  570. ACCEL_Y_MIN = value_param;
  571. else if (type_param == 'M')
  572. ACCEL_Y_MAX = value_param;
  573. }
  574. else if (axis_param == 'z') // z value
  575. {
  576. if (type_param == 'm')
  577. ACCEL_Z_MIN = value_param;
  578. else if (type_param == 'M')
  579. ACCEL_Z_MAX = value_param;
  580. }
  581. recalculateAccelCalibration();
  582. }
  583. else if (input_param == 'm') // Calibrate _m_agnetometer (basic)
  584. {
  585. //disable extended magnetometer calibration
  586. CALIBRATION__MAGN_USE_EXTENDED = false;
  587. char axis_param = readChar();
  588. char type_param = readChar();
  589. float value_param = Serial.parseFloat();
  590. if (axis_param == 'x') // x value
  591. {
  592. if (type_param == 'm')
  593. MAGN_X_MIN = value_param;
  594. else if (type_param == 'M')
  595. MAGN_X_MAX = value_param;
  596. }
  597. else if (axis_param == 'y') // y value
  598. {
  599. if (type_param == 'm')
  600. MAGN_Y_MIN = value_param;
  601. else if (type_param == 'M')
  602. MAGN_Y_MAX = value_param;
  603. }
  604. else if (axis_param == 'z') // z value
  605. {
  606. if (type_param == 'm')
  607. MAGN_Z_MIN = value_param;
  608. else if (type_param == 'M')
  609. MAGN_Z_MAX = value_param;
  610. }
  611. recalculateMagnCalibration();
  612. }
  613. else if (input_param == 'c') // Calibrate magnetometerellipsoid_c_enter (extended)
  614. {
  615. //enable extended magnetometer calibration
  616. CALIBRATION__MAGN_USE_EXTENDED = true;
  617. char axis_param = readChar();
  618. float value_param = Serial.parseFloat();
  619. if (axis_param == 'x') // x value
  620. magn_ellipsoid_center[0] = value_param;
  621. else if (axis_param == 'y') // y value
  622. magn_ellipsoid_center[1] = value_param;
  623. else if (axis_param == 'z') // z value
  624. magn_ellipsoid_center[2] = value_param;
  625. }
  626. else if (input_param == 't') // Calibrate magnetometerellipsoid_t_ransform (extended)
  627. {
  628. //enable extended magnetometer calibration
  629. CALIBRATION__MAGN_USE_EXTENDED = true;
  630. char axis_param = readChar();
  631. char type_param = readChar();
  632. float value_param = Serial.parseFloat();
  633. if (axis_param == 'x') // x value
  634. {
  635. if (type_param == 'X')
  636. magn_ellipsoid_transform[0][0] = value_param;
  637. else if (type_param == 'Y')
  638. magn_ellipsoid_transform[0][1] = value_param;
  639. else if (type_param == 'Z')
  640. magn_ellipsoid_transform[0][2] = value_param;
  641. }
  642. else if (axis_param == 'y') // y value
  643. {
  644. if (type_param == 'X')
  645. magn_ellipsoid_transform[1][0] = value_param;
  646. else if (type_param == 'Y')
  647. magn_ellipsoid_transform[1][1] = value_param;
  648. else if (type_param == 'Z')
  649. magn_ellipsoid_transform[1][2] = value_param;
  650. }
  651. else if (axis_param == 'z') // z value
  652. {
  653. if (type_param == 'X')
  654. magn_ellipsoid_transform[2][0] = value_param;
  655. else if (type_param == 'Y')
  656. magn_ellipsoid_transform[2][1] = value_param;
  657. else if (type_param == 'Z')
  658. magn_ellipsoid_transform[2][2] = value_param;
  659. }
  660. }
  661. else if (input_param == 'g') // Calibrate _g_yro
  662. {
  663. char axis_param = readChar();
  664. float value_param = Serial.parseFloat();
  665. if (axis_param == 'x') // x value
  666. GYRO_AVERAGE_OFFSET_X = value_param;
  667. else if (axis_param == 'y') // y value
  668. GYRO_AVERAGE_OFFSET_Y = value_param;
  669. else if (axis_param == 'z') // z value
  670. GYRO_AVERAGE_OFFSET_Z = value_param;
  671. }
  672. }
  673. #if OUTPUT__HAS_RN_BLUETOOTH == true
  674. // Read messages from bluetooth module
  675. // For this to work, the connect/disconnect message prefix of the module has to be set to "#".
  676. else if (command == 'C') // Bluetooth "#CONNECT" message (does the same as "#o1")
  677. turn_output_stream_on();
  678. else if (command == 'D') // Bluetooth "#DISCONNECT" message (does the same as "#o0")
  679. turn_output_stream_off();
  680. #endif // OUTPUT__HAS_RN_BLUETOOTH == true
  681. }
  682. else
  683. { } // Skip character
  684. }
  685. // Time to read the sensors again?
  686. if((millis() - timestamp) >= OUTPUT__DATA_INTERVAL)
  687. {
  688. timestamp_old = timestamp;
  689. timestamp = millis();
  690. if (timestamp > timestamp_old)
  691. G_Dt = (float) (timestamp - timestamp_old) / 1000.0f; // Real time of loop run. We use this on the DCM algorithm (gyro integration time)
  692. else G_Dt = 0;
  693. // Update sensor readings
  694. read_sensors();
  695. if (output_mode == OUTPUT__MODE_CALIBRATE_SENSORS) // We're in calibration mode
  696. {
  697. check_reset_calibration_session(); // Check if this session needs a reset
  698. if (output_stream_on || output_single_on) output_calibration(curr_calibration_sensor);
  699. }
  700. else if (output_mode == OUTPUT__MODE_ANGLES) // Output angles
  701. {
  702. // Apply sensor calibration
  703. compensate_sensor_errors();
  704. // Run DCM algorithm
  705. Compass_Heading(); // Calculate magnetic heading
  706. Matrix_update();
  707. Normalize();
  708. Drift_correction();
  709. Euler_angles();
  710. if (output_stream_on || output_single_on) output_angles();
  711. }
  712. else if (output_mode == OUTPUT__MODE_ANGLES_AG_SENSORS) // Output angles + accel + rot. vel
  713. {
  714. // Apply sensor calibration
  715. compensate_sensor_errors();
  716. // Run DCM algorithm
  717. Compass_Heading(); // Calculate magnetic heading
  718. Matrix_update();
  719. Normalize();
  720. Drift_correction();
  721. Euler_angles();
  722. if (output_stream_on || output_single_on) output_both_angles_and_sensors_text();
  723. }
  724. else // Output sensor values
  725. {
  726. if (output_stream_on || output_single_on) output_sensors();
  727. }
  728. output_single_on = false;
  729. #if DEBUG__PRINT_LOOP_TIME == true
  730. Serial.print("loop time (ms) = ");
  731. Serial.println(millis() - timestamp);
  732. #endif
  733. }
  734. #if DEBUG__PRINT_LOOP_TIME == true
  735. else
  736. {
  737. Serial.println("waiting...");
  738. }
  739. #endif
  740. }