0.2.0
|
The INS status bitfield. More...
Public Types | |
enum class | Mode { NotTracking , Aligning , Tracking , LossOfGNSS } |
Indicates the current mode of the INS filter. More... | |
Public Member Functions | |
constexpr bool | errorGnss () const |
Extract the GNSS Error from the ins status. | |
constexpr bool | errorIMU () const |
Extract the IMU Error from the ins status. | |
constexpr bool | errorMagPres () const |
Extract the Mag/Pres Error from the ins status. | |
constexpr bool | gpsCompass () const |
Extract the GPS Compass from the ins status. | |
constexpr bool | gpsFix () const |
Extract the GPS Fix from the ins status. | |
constexpr bool | gpsHeadingIns () const |
Extract the GPS Heading INS from the ins status. | |
InsStatus ()=default | |
Default constructor. | |
InsStatus (uint16_t status) | |
constexpr Mode | mode () const |
Extract the current mode of the INS filter from the ins status. | |
InsStatus & | operator= (const uint16_t &status) |
Assignment operator. | |
constexpr uint16_t & | status () |
Returns a reference to the status. | |
The INS status bitfield.
Bit | Name | Description 0+1 | Mode | Indicates the current mode of the INS filter. | 0 = Not tracking. GNSS Compass is initializing. Output heading is based on magnetometer measurements. | 1 = Aligning. | INS Filter is dynamically aligning. | For a stationary startup: GNSS Compass has initialized and INS Filter is | aligning from the magnetic heading to the GNSS Compass heading. | For a dynamic startup: INS Filter has initialized and is dynamically aligning to | True North heading. | In operation, if the INS Filter drops from INS Mode 2 back down to 1, the | attitude uncertainty has increased above 2 degrees. | 2 = Tracking. The INS Filter is tracking and operating within specification. | 3 = Loss of GNSS. A GNSS outage has lasted more than 45 seconds. The INS Filter will | no longer update the position and velocity outputs, but the attitude remains valid. 2 | GpsFix | Indicates whether the GNSS has a proper fix. 4 | IMU Error | High if IMU communication error is detected. 5 | Mag/Pres Error | High if Magnetometer or Pressure sensor error is detected. 6 | GNSS Error | High if GNSS communication error is detected, 8 | GpsHeadingIns | In stationary operation, if set the INS Filter has fully aligned to the GNSS Compass solution. | In dynamic operation, the GNSS Compass solution is currently aiding the INS Filter heading solution. 9 | GpsCompass | Indicates if the GNSS compass is operational and reporting a heading solution.
|
strong |
Indicates the current mode of the INS filter.
|
inlineexplicit |
Constructor
[in] | status | Status to set |
|
inline |
Assignment operator.
[in] | status | Status to set |