Hummingbird Flight Software
Flight software for the Hummingbird FCU quadcopter flight controller. Designed to run on the Teensy 4.1. Developed with VSCode+PlatformIO.
compass.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // MAGNETOMETER/COMAPSS OBJECT
3 //
4 // Code By: Michael Wrona
5 // Created : 4 Mar 2021
6 // ----------------------------------------------------------------------------
12 #pragma once
13 
14 
15 #include <Arduino.h>
16 #include <Wire.h>
17 #include <math.h>
18 #include "hummingbird_config.h"
20 #include "maths/vectors.h"
21 #include "constants.h"
22 #include "maths/math_functs.h"
24 
25 
26 #if defined(DEBUG) && defined(DEBUG_PORT)
27  /* Print compass debug messages to the debug port. Both DEBUG and DEBUG_PORT in hummingbird_config.h must be defined. */
28  #define MAGCOMPASS_DEBUG
29 #endif
30 
31 
32 /* CONFIGURATION PARAMETERS */
33 constexpr LIS3MDL_MeasRange_t MAGCOMPASS_RANGE = LIS3MDL_RANGE_4G; // Magnetometer measurement range
34 
40 // #define MAGCOMPASS_DO_NOT_ROTATE
41 
42 
44 {
45 public:
46  MagCompass(TwoWire *userWire = &SENSOR_I2C);
47  ~MagCompass();
48 
49  // Do not allow copies
50  static MagCompass &GetInstance();
51  MagCompass(const MagCompass &) = delete;
52  MagCompass &operator=(const MagCompass &) = delete;
53 
54  bool Initialize();
55  bool Update();
56  float GetHeading(Vectorf AccelMeas);
57 
58  uint32_t prevUpdateMicros; // [us] Previous update micros()
59  Vectorf Mag; // [mx, my, mz], [uT] Magnetometer readings (calibrated)
60  Vectorf MagRaw; // [mx, my, mz], [uT] Raw, uncalibrated readings
61 
62 protected:
63 private:
64  float heading; // [rad], [0, 2pi) Tilt-compensated magnetic heading
67  TwoWire *SensorWire;
68 };
69 
70 // Only one instance of MagCompass
71 extern MagCompass &Compass;
STMicroelectronics LIS3MDL magnetometer sensor class.
Definition: lis3mdl_magnetometer.h:72
Decide whether or not to rotate magnetometer measurements.
Definition: compass.h:44
bool Update()
Update the compass.
Definition: compass.cpp:74
LIS3MDL_MeasRange_t magMeasRange
Definition: compass.h:66
LIS3MDL_Mag MagSensor
Definition: compass.h:65
float GetHeading(Vectorf AccelMeas)
Compute and return tilt-compensated magnetic heading based on accelerometer data.
Definition: compass.cpp:129
MagCompass & operator=(const MagCompass &)=delete
uint32_t prevUpdateMicros
Definition: compass.h:58
MagCompass(TwoWire *userWire=&SENSOR_I2C)
The compass class is in charge of taking magnetometer measurements and computing tilt-compensated (ma...
Definition: compass.cpp:26
~MagCompass()
Definition: compass.cpp:176
float heading
Definition: compass.h:64
TwoWire * SensorWire
Definition: compass.h:67
bool Initialize()
Initialize the compass.
Definition: compass.cpp:42
static MagCompass & GetInstance()
Definition: compass.cpp:179
MagCompass(const MagCompass &)=delete
Vectorf Mag
Definition: compass.h:59
Vectorf MagRaw
Definition: compass.h:60
A vector object is definied by it's rows/length.
Definition: vectors.h:46
constexpr LIS3MDL_MeasRange_t MAGCOMPASS_RANGE
The compass class is in charge of taking magnetometer measurements and computing tilt-compensated (ma...
Definition: compass.h:33
MagCompass & Compass
Definition: compass.cpp:185
#define SENSOR_I2C
UBER-EXTREME CAUTION SHOULD BE USED CHANGING PARAMETERS IN THIS FILE.
Definition: hummingbird_config.h:26
LIS3MDL_MeasRange_t
LIS3MDL measurement ranges (gauss)
Definition: lis3mdl_magnetometer.h:60
@ LIS3MDL_RANGE_4G
Definition: lis3mdl_magnetometer.h:61