|
HF-BNO08x
0.1.0-dev
|
Unified driver for the BNO08x IMU – SH-2 mode, RVC mode, and DFU. More...
#include <bno08x.hpp>
Public Member Functions | |
| BNO085 (CommType &comm) noexcept | |
| Construct the driver with a communication interface. | |
| ~BNO085 () noexcept | |
| Destructor. Closes active SH-2/RVC sessions. | |
SH-2 Mode API | |
These methods are valid when GetInterfaceType() returns I2C, SPI, or UART. They provide full access to the BNO08x sensor hub via the SH-2 protocol. | |
| bool | Begin () noexcept |
| Initialise the sensor in SH-2 mode. | |
| void | Close () noexcept |
| Close the currently active session and release transport resources. | |
| bool | EnableSensor (BNO085Sensor sensor, uint32_t interval_ms, float sensitivity=0.0f) noexcept |
| Enable periodic reporting for a sensor. | |
| bool | DisableSensor (BNO085Sensor sensor) noexcept |
| Disable reporting for a sensor. | |
| void | SetCallback (SensorCallback cb) noexcept |
| Register a callback for SH-2 sensor events. | |
| bool | HasNewData (BNO085Sensor sensor) const |
| Check if new data is available for a sensor. | |
| SensorEvent | GetLatest (BNO085Sensor sensor) noexcept |
| Retrieve the most recent event for a sensor. | |
| void | Update () noexcept |
| Pump the SH-2 service loop. | |
RVC Mode API | |
These methods are valid when GetInterfaceType() returns UARTRVC. RVC mode provides simplified yaw/pitch/roll + acceleration data via UART at 115200 baud without the overhead of the SH-2 protocol. | |
| void | SetRvcCallback (RvcCallback cb) noexcept |
| Register a callback for decoded RVC frames. | |
| bool | BeginRvc () noexcept |
| Initialise RVC mode. | |
| void | ServiceRvc () noexcept |
| Poll for RVC frames and dispatch callbacks. | |
| void | CloseRvc () noexcept |
| Stop RVC processing and close the transport. | |
Common API | |
These methods work regardless of the interface type. | |
| int | GetLastError () const |
| Get the last error code from the SH-2 driver. | |
| BNO085DriverState | GetState () const noexcept |
| Get the current high-level driver state. | |
| void | HardwareReset (uint32_t lowMs=2) noexcept |
| Perform a hardware reset via the RSTN pin. | |
| void | SetBootPin (bool state) noexcept |
| Drive the BOOTN pin to enter/exit DFU bootloader mode. | |
| void | SetWakePin (bool state) noexcept |
| Drive the WAKE pin (SPI mode only). | |
| void | SelectInterface (BNO085Interface iface) noexcept |
| Select the host interface by driving PS0/PS1 pins. | |
| int | Dfu (const HcBin_t &fw=firmware) noexcept |
| Perform a Device Firmware Update (DFU). | |
| int | DfuWithOptions (const HcBin_t &fw, const DfuOptions &options) noexcept |
| Perform DFU with explicit validation and transfer options. | |
| int | DfuFromMemory (const DfuMemoryImage &image, const DfuOptions &options={}) noexcept |
| Perform DFU from an in-memory firmware image. | |
| int | DfuFromMemory (const uint8_t *data, uint32_t len, const char *partNumber="1000-3608", const DfuOptions &options={}) noexcept |
| Convenience overload for in-memory DFU. | |
| bool | EnterBootloader (uint32_t resetLowMs=10, uint32_t settleMs=50) noexcept |
| Enter bootloader mode using BOOTN + reset pin sequence. | |
| bool | ExitBootloaderAndReboot (uint32_t resetLowMs=2, uint32_t settleMs=100) noexcept |
| Exit bootloader mode and reboot into application firmware. | |
| int | RunDfuFromMemory (const DfuMemoryImage &image, const DfuOptions &options={}, uint32_t enterResetLowMs=10, uint32_t enterSettleMs=50, uint32_t exitResetLowMs=2, uint32_t exitSettleMs=100) noexcept |
| Full class-aware DFU workflow: enter bootloader -> transfer firmware -> reboot to app. | |
Static Public Member Functions | |
| static constexpr const char * | GetDriverVersion () noexcept |
| Get the compiled driver version string. | |
| static constexpr uint8_t | GetDriverVersionMajor () noexcept |
| Get the compiled driver major version number. | |
| static constexpr uint8_t | GetDriverVersionMinor () noexcept |
| Get the compiled driver minor version number. | |
| static constexpr uint8_t | GetDriverVersionPatch () noexcept |
| Get the compiled driver patch version number. | |
Unified driver for the BNO08x IMU – SH-2 mode, RVC mode, and DFU.
A single template class that adapts to the transport type at compile time. The CommInterface::GetInterfaceType() method determines which mode of operation is valid:
| Interface Type | Valid Operations |
|---|---|
| I2C / SPI / UART | Begin(), Update(), EnableSensor(), Dfu(), etc. |
| UARTRVC | BeginRvc(), ServiceRvc(), CloseRvc() |
Calling a mode-incompatible method returns false or SH2_ERR gracefully. The active mode is tracked by an internal state machine exposed via GetState(). Illegal transitions are rejected with SH2_ERR_OP_IN_PROGRESS or SH2_ERR_BAD_PARAM.
Error policy:
SH2_ERR_BAD_PARAMSH2_ERR_OP_IN_PROGRESSGetState, HasNewData, GetLatest) are side-effect free with respect to last_error_.The driver automatically re-enables configured sensors after a sensor reset (handled internally by the async event callback).
| CommType | Platform-specific transport. Must inherit from bno08x::CommInterface<CommType>. |
Construct the driver with a communication interface.
| [in] | comm | Reference to the transport (must outlive this object). |
Destructor. Closes active SH-2/RVC sessions.
|
noexcept |
Initialise the sensor in SH-2 mode.
Opens the communication bus, connects to the SH-2 layer, sends the reinitialize command, and registers the internal sensor/event callbacks.
true on success, false on failure or wrong interface type.
|
noexcept |
Initialise RVC mode.
Open the UART transport and start the RVC frame parser.
Opens the UART transport and starts the internal frame parser. The sensor must have PS0/PS1 set for RVC mode at boot time.
true on success, false on failure or wrong interface type.
|
noexcept |
Close the currently active session and release transport resources.
If SH-2 is active, calls sh2_close() and closes the transport. If RVC is active, closes the UART transport and stops the parser. If DFU is in progress, the call is rejected and last_error_ is set to SH2_ERR_OP_IN_PROGRESS. Safe to call multiple times.
|
noexcept |
Stop RVC processing and close the transport.
Close the UART transport and deactivate the RVC parser.
Convenience API for explicit RVC teardown. Close() can also be used to close whichever mode is currently active.
Perform a Device Firmware Update (DFU).
Execute DFU with default validation options.
The sensor must already be in bootloader mode (hold BOOTN LOW during reset). The method validates the firmware image, then transfers it in packets with CRC-16 and ACK/NAK retry logic.
| [in] | fw | Firmware image. Defaults to the compiled-in stub from firmware-bno.c. Use MemoryFirmware for runtime images. |
SH2_OK (0) on success, or a negative SH-2 error code.
|
noexcept |
Perform DFU from an in-memory firmware image.
Execute DFU from an in-memory image descriptor.
Wraps image in a MemoryFirmware adapter internally and executes the same DFU protocol as DfuWithOptions().
|
noexcept |
Convenience overload for in-memory DFU.
Convenience overload for memory DFU from raw pointers.
|
noexcept |
Perform DFU with explicit validation and transfer options.
Execute the full DFU firmware transfer with configurable policy.
Uses the same HcBin image interface as Dfu(), but allows metadata policy, packet-size override, and progress reporting customization.
Validates firmware metadata/length, opens the bootloader transport, sends app size + packet size, streams firmware data with CRC+ACK retry, and optionally reports progress.
|
noexcept |
Disable reporting for a sensor.
Disable reporting for a sensor by setting its interval to zero.
| [in] | sensor | Which sensor to disable. |
true if successful.
|
noexcept |
Enable periodic reporting for a sensor.
| [in] | sensor | Which sensor to enable. |
| [in] | interval_ms | Report interval in milliseconds (e.g. 10 = 100 Hz). Use 0 for on-change sensors (step counter, tap, etc.). |
| [in] | sensitivity | Change sensitivity threshold for on-change sensors. Set to 0.0 to disable sensitivity filtering. |
true if the sensor was configured successfully.Converts the millisecond interval to microseconds and forwards to the SH-2 configuration API. The interval and sensitivity are cached so they can be automatically re-applied after a sensor reset.
|
noexcept |
Enter bootloader mode using BOOTN + reset pin sequence.
Enter bootloader mode via BOOTN+reset sequence.
Holds BOOTN low, pulses reset, then releases BOOTN. Requires a transport with BOOTN/RSTN wiring support.
|
noexcept |
Exit bootloader mode and reboot into application firmware.
Exit bootloader mode and reboot application firmware.
Ensures BOOTN is released high, pulses reset, then waits for boot.
|
inlinestaticconstexprnoexcept |
Get the compiled driver version string.
|
inlinestaticconstexprnoexcept |
Get the compiled driver major version number.
|
inlinestaticconstexprnoexcept |
Get the compiled driver minor version number.
|
inlinestaticconstexprnoexcept |
Get the compiled driver patch version number.
|
inline |
Get the last error code from the SH-2 driver.
sh2_err.h for values.
|
noexcept |
Retrieve the most recent event for a sensor.
Retrieve the most recent event for a sensor and clear unread flag.
Returns a decoded SensorEvent populated with the latest values. Which fields are meaningful depends on the sensor type.
| [in] | sensor | Which sensor to query. Calling this method clears the unread-data flag for sensor. If the driver is not in Sh2Active state, returns a default event and leaves cached SH-2 flags unchanged. |
|
inlinenoexcept |
Get the current high-level driver state.
|
noexcept |
Perform a hardware reset via the RSTN pin.
Assert RSTN for lowMs, then release and wait for boot.
Drives RSTN LOW for lowMs milliseconds, then releases it HIGH and waits 50 ms for the sensor to boot.
| [in] | lowMs | Duration to hold RSTN LOW (default 2 ms). |
The 50 ms post-release delay allows the sensor to complete its boot sequence before any I2C/SPI/UART transactions.
| bool BNO085< CommType >::HasNewData | ( | BNO085Sensor | sensor | ) | const |
Check if new data is available for a sensor.
Check the new-data flag for a sensor.
The flag is set when a report arrives and cleared when GetLatest() is called. Callback dispatch does not clear this flag, which allows mixed callback + polling usage.
Returns false unless the driver is currently in Sh2Active state.
| [in] | sensor | Which sensor to check. |
true if unread data is available.
|
noexcept |
Full class-aware DFU workflow: enter bootloader -> transfer firmware -> reboot to app.
Full workflow: enter bootloader, transfer memory image, reboot app.
|
noexcept |
Select the host interface by driving PS0/PS1 pins.
Drive PS0/PS1 pins to select the host interface.
This is only useful if the PS pins are connected to controllable GPIOs (rare – most boards hard-wire them).
| [in] | iface | Desired interface. |
PS pins are sampled at reset. This is only useful if the pins are connected to controllable GPIOs.
|
noexcept |
Poll for RVC frames and dispatch callbacks.
Read all available UART bytes and parse RVC frames.
Reads all available UART bytes, feeds them into the frame parser, and invokes the RVC callback for each complete valid frame. Call this in your main loop or an RTOS task.
Each byte is fed into a 19-byte sliding window. When a valid frame is detected (0xAA 0xAA header + matching checksum), the fields are extracted, decoded to floating-point, and dispatched to the RVC callback.
|
noexcept |
Drive the BOOTN pin to enter/exit DFU bootloader mode.
Forward BOOTN control to the CommInterface.
| [in] | state | true = drive LOW (enter bootloader), false = HIGH. |
|
noexcept |
Register a callback for SH-2 sensor events.
Register a callback invoked for every received SH-2 sensor event.
The callback is invoked from within Update() whenever the SH-2 library delivers a new sensor report. Only one callback can be registered at a time; calling this again replaces the previous callback.
| [in] | cb | Callback function or lambda. Pass {} to clear. |
|
noexcept |
Register a callback for decoded RVC frames.
Register a callback invoked for every decoded RVC frame.
The callback is invoked from within ServiceRvc() each time a valid 19-byte RVC frame is received and decoded.
| [in] | cb | Callback function or lambda. Pass {} to clear. |
|
noexcept |
Drive the WAKE pin (SPI mode only).
Forward WAKE control to the CommInterface (SPI only).
| [in] | state | true = drive LOW (wake sensor), false = release. |
|
noexcept |
Pump the SH-2 service loop.
Service the SH-2 protocol. Invokes sensor and async callbacks.
Must be called frequently (every 5-10 ms or faster) to keep data flowing between the host and the sensor hub. Sensor callbacks and async event handlers are invoked from within this method.